From 1513b31a3d21e7d988e474927168fdf068292105 Mon Sep 17 00:00:00 2001 From: "M.A. Gomez" Date: Sun, 9 Jul 2023 14:39:05 +0200 Subject: [PATCH 01/16] [ADD]: rtklib pos res to pvt_kf --- src/algorithms/PVT/libs/pvt_kf.cc | 18 +++++++++++++----- src/algorithms/PVT/libs/pvt_kf.h | 3 ++- src/algorithms/PVT/libs/rtklib_solver.cc | 8 +++++++- 3 files changed, 22 insertions(+), 7 deletions(-) diff --git a/src/algorithms/PVT/libs/pvt_kf.cc b/src/algorithms/PVT/libs/pvt_kf.cc index 10083b221..72429f160 100644 --- a/src/algorithms/PVT/libs/pvt_kf.cc +++ b/src/algorithms/PVT/libs/pvt_kf.cc @@ -21,6 +21,7 @@ void Pvt_Kf::init_kf(const arma::vec& p, const arma::vec& v, + const arma::vec& res_p, double solver_interval_s, double measures_ecef_pos_sd_m, double measures_ecef_vel_sd_ms, @@ -40,9 +41,9 @@ void Pvt_Kf::init_kf(const arma::vec& p, d_H = arma::eye(6, 6); // measurement matrix static covariances - d_R = {{pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0, 0.0}, - {0.0, pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0}, - {0.0, 0.0, pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0}, + d_R = {{res_p[0], res_p[3], res_p[5], 0.0, 0.0, 0.0}, + {res_p[3], res_p[1], res_p[4], 0.0, 0.0, 0.0}, + {res_p[4], res_p[5], res_p[2], 0.0, 0.0, 0.0}, {0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, {0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0}, {0.0, 0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0)}}; @@ -80,19 +81,26 @@ void Pvt_Kf::init_kf(const arma::vec& p, } -void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v) +void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p) { // Kalman loop // Prediction d_x_new_old = d_F * d_x_old_old; d_P_new_old = d_F * d_P_old_old * d_F.t() + d_Q; + // Measurement residuals + d_R(0,0) = res_p[0]; d_R(0,1) = res_p[3]; d_R(0,2) = res_p[5]; + d_R(1,0) = res_p[3]; d_R(1,1) = res_p[1]; d_R(1,2) = res_p[4]; + d_R(2,0) = res_p[5]; d_R(2,1) = res_p[4]; d_R(2,2) = res_p[2]; + // Measurement update arma::vec z = arma::join_cols(p, v); arma::mat K = d_P_new_old * d_H.t() * arma::inv(d_H * d_P_new_old * d_H.t() + d_R); // Kalman gain d_x_new_new = d_x_new_old + K * (z - d_H * d_x_new_old); - d_P_new_new = (arma::eye(6, 6) - K * d_H) * d_P_new_old; + arma::mat A = (arma::eye(6, 6) - K * d_H); + d_P_new_new = A * d_P_new_old * A.t() + K * d_R * K.t(); + // prepare data for next KF epoch d_x_old_old = d_x_new_new; diff --git a/src/algorithms/PVT/libs/pvt_kf.h b/src/algorithms/PVT/libs/pvt_kf.h index 26dc25a43..dc5b088ff 100644 --- a/src/algorithms/PVT/libs/pvt_kf.h +++ b/src/algorithms/PVT/libs/pvt_kf.h @@ -37,12 +37,13 @@ public: virtual ~Pvt_Kf() = default; void init_kf(const arma::vec& p, const arma::vec& v, + const arma::vec& res_p, double solver_interval_s, double measures_ecef_pos_sd_m, double measures_ecef_vel_sd_ms, double system_ecef_pos_sd_m, double system_ecef_vel_sd_ms); - void run_Kf(const arma::vec& p, const arma::vec& v); + void run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p); void get_pvt(arma::vec& p, arma::vec& v); bool initialized{false}; diff --git a/src/algorithms/PVT/libs/rtklib_solver.cc b/src/algorithms/PVT/libs/rtklib_solver.cc index e17edfa14..23ffa062d 100644 --- a/src/algorithms/PVT/libs/rtklib_solver.cc +++ b/src/algorithms/PVT/libs/rtklib_solver.cc @@ -1552,9 +1552,12 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ { arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; + arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], + pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; d_pvt_kf.init_kf(p, v, + res_p, d_conf.observable_interval_ms / 1000.0, d_conf.measures_ecef_pos_sd_m, d_conf.measures_ecef_vel_sd_ms, @@ -1565,7 +1568,10 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ { arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; - d_pvt_kf.run_Kf(p, v); + arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], + pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; + + d_pvt_kf.run_Kf(p, v, res_p); d_pvt_kf.get_pvt(p, v); pvt_sol.rr[0] = p[0]; // [m] pvt_sol.rr[1] = p[1]; // [m] From c0d484f80dd70270fa549c87de7faec9a8157dca Mon Sep 17 00:00:00 2001 From: "M.A. Gomez" Date: Mon, 10 Jul 2023 14:38:39 +0200 Subject: [PATCH 02/16] [Merge] branches --- src/algorithms/PVT/libs/pvt_kf.cc | 77 ++++++++++++++++-------- src/algorithms/PVT/libs/pvt_kf.h | 11 ++-- src/algorithms/PVT/libs/rtklib_solver.cc | 16 ++--- src/algorithms/PVT/libs/rtklib_solver.h | 2 +- 4 files changed, 65 insertions(+), 41 deletions(-) diff --git a/src/algorithms/PVT/libs/pvt_kf.cc b/src/algorithms/PVT/libs/pvt_kf.cc index 72429f160..9608890c6 100644 --- a/src/algorithms/PVT/libs/pvt_kf.cc +++ b/src/algorithms/PVT/libs/pvt_kf.cc @@ -19,17 +19,17 @@ #include -void Pvt_Kf::init_kf(const arma::vec& p, +void Pvt_Kf::init_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p, - double solver_interval_s, + double update_interval_s, double measures_ecef_pos_sd_m, double measures_ecef_vel_sd_ms, double system_ecef_pos_sd_m, double system_ecef_vel_sd_ms) { // Kalman Filter class variables - const double Ti = solver_interval_s; + const double Ti = update_interval_s; d_F = {{1.0, 0.0, 0.0, Ti, 0.0, 0.0}, {0.0, 1.0, 0.0, 0.0, Ti, 0.0}, @@ -69,7 +69,7 @@ void Pvt_Kf::init_kf(const arma::vec& p, d_x_old_old.subvec(0, 2) = p; d_x_old_old.subvec(3, 5) = v; - initialized = true; + d_initialized = true; DLOG(INFO) << "Ti: " << Ti; DLOG(INFO) << "F: " << d_F; @@ -81,35 +81,60 @@ void Pvt_Kf::init_kf(const arma::vec& p, } +bool Pvt_Kf::is_initialized() const +{ + return d_initialized; +} + + +void Pvt_Kf::reset_Kf() +{ + d_initialized = false; +} + + void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p) { - // Kalman loop - // Prediction - d_x_new_old = d_F * d_x_old_old; - d_P_new_old = d_F * d_P_old_old * d_F.t() + d_Q; + if (d_initialized) + { + // Kalman loop + // Prediction + d_x_new_old = d_F * d_x_old_old; + d_P_new_old = d_F * d_P_old_old * d_F.t() + d_Q; - // Measurement residuals - d_R(0,0) = res_p[0]; d_R(0,1) = res_p[3]; d_R(0,2) = res_p[5]; - d_R(1,0) = res_p[3]; d_R(1,1) = res_p[1]; d_R(1,2) = res_p[4]; - d_R(2,0) = res_p[5]; d_R(2,1) = res_p[4]; d_R(2,2) = res_p[2]; + // Measurement update + try + { + // Measurement residuals + d_R(0,0) = res_p[0]; d_R(0,1) = res_p[3]; d_R(0,2) = res_p[5]; + d_R(1,0) = res_p[3]; d_R(1,1) = res_p[1]; d_R(1,2) = res_p[4]; + d_R(2,0) = res_p[5]; d_R(2,1) = res_p[4]; d_R(2,2) = res_p[2]; - // Measurement update - arma::vec z = arma::join_cols(p, v); - arma::mat K = d_P_new_old * d_H.t() * arma::inv(d_H * d_P_new_old * d_H.t() + d_R); // Kalman gain + // Measurement update + arma::vec z = arma::join_cols(p, v); + arma::mat K = d_P_new_old * d_H.t() * arma::inv(d_H * d_P_new_old * d_H.t() + d_R); // Kalman gain - d_x_new_new = d_x_new_old + K * (z - d_H * d_x_new_old); - arma::mat A = (arma::eye(6, 6) - K * d_H); - d_P_new_new = A * d_P_new_old * A.t() + K * d_R * K.t(); - - - // prepare data for next KF epoch - d_x_old_old = d_x_new_new; - d_P_old_old = d_P_new_new; + d_x_new_new = d_x_new_old + K * (z - d_H * d_x_new_old); + arma::mat A = (arma::eye(6, 6) - K * d_H); + d_P_new_new = A * d_P_new_old * A.t() + K * d_R * K.t(); + // prepare data for next KF epoch + d_x_old_old = d_x_new_new; + d_P_old_old = d_P_new_new; + } + catch (...) + { + d_x_new_new = d_x_new_old; + this->reset_Kf(); + } + } } -void Pvt_Kf::get_pvt(arma::vec& p, arma::vec& v) +void Pvt_Kf::get_pv_Kf(arma::vec& p, arma::vec& v) const { - p = d_x_new_new.subvec(0, 2); - v = d_x_new_new.subvec(3, 5); + if (d_initialized) + { + p = d_x_new_new.subvec(0, 2); + v = d_x_new_new.subvec(3, 5); + } } diff --git a/src/algorithms/PVT/libs/pvt_kf.h b/src/algorithms/PVT/libs/pvt_kf.h index dc5b088ff..22640f3ff 100644 --- a/src/algorithms/PVT/libs/pvt_kf.h +++ b/src/algorithms/PVT/libs/pvt_kf.h @@ -35,17 +35,18 @@ class Pvt_Kf public: Pvt_Kf() = default; virtual ~Pvt_Kf() = default; - void init_kf(const arma::vec& p, + void init_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p, - double solver_interval_s, + double update_interval_s, double measures_ecef_pos_sd_m, double measures_ecef_vel_sd_ms, double system_ecef_pos_sd_m, double system_ecef_vel_sd_ms); + bool is_initialized() const; void run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p); - void get_pvt(arma::vec& p, arma::vec& v); - bool initialized{false}; + void get_pv_Kf(arma::vec& p, arma::vec& v) const; + void reset_Kf(); private: // Kalman Filter class variables @@ -59,9 +60,11 @@ private: arma::vec d_x_old_old; arma::vec d_x_new_old; arma::vec d_x_new_new; + bool d_initialized{false}; }; /** \} */ /** \} */ #endif // GNSS_SDR_Pvt_Kf_H + diff --git a/src/algorithms/PVT/libs/rtklib_solver.cc b/src/algorithms/PVT/libs/rtklib_solver.cc index 23ffa062d..e1a003a46 100644 --- a/src/algorithms/PVT/libs/rtklib_solver.cc +++ b/src/algorithms/PVT/libs/rtklib_solver.cc @@ -56,8 +56,6 @@ Rtklib_Solver::Rtklib_Solver(const rtk_t &rtk, d_flag_dump_enabled(flag_dump_to_file), d_flag_dump_mat_enabled(flag_dump_to_mat) { - this->set_averaging_flag(false); - // see freq index at src/algorithms/libs/rtklib/rtklib_rtkcmn.cc // function: satwavelen d_rtklib_freq_index[0] = 0; @@ -900,7 +898,7 @@ void Rtklib_Solver::get_current_has_obs_correction(const std::string &signal, ui } -bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_map, bool flag_averaging) +bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_map, double kf_update_interval_s) { std::map::const_iterator gnss_observables_iter; std::map::const_iterator galileo_ephemeris_iter; @@ -911,8 +909,6 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ const Glonass_Gnav_Utc_Model &gnav_utc = this->glonass_gnav_utc_model; - this->set_averaging_flag(flag_averaging); - // ******************************************************************************** // ****** PREPARE THE DATA (SV EPHEMERIS AND OBSERVATIONS) ************************ // ******************************************************************************** @@ -1509,7 +1505,7 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ this->set_num_valid_observations(0); if (d_conf.enable_pvt_kf == true) { - d_pvt_kf.initialized = false; + d_pvt_kf.reset_Kf(); } } else @@ -1548,17 +1544,17 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ if (d_conf.enable_pvt_kf == true) { - if (d_pvt_kf.initialized == false) + if (d_pvt_kf.is_initialized() == false) { arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; - d_pvt_kf.init_kf(p, + d_pvt_kf.init_Kf(p, v, res_p, - d_conf.observable_interval_ms / 1000.0, + kf_update_interval_s, d_conf.measures_ecef_pos_sd_m, d_conf.measures_ecef_vel_sd_ms, d_conf.system_ecef_pos_sd_m, @@ -1572,7 +1568,7 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; d_pvt_kf.run_Kf(p, v, res_p); - d_pvt_kf.get_pvt(p, v); + d_pvt_kf.get_pv_Kf(p, v); pvt_sol.rr[0] = p[0]; // [m] pvt_sol.rr[1] = p[1]; // [m] pvt_sol.rr[2] = p[2]; // [m] diff --git a/src/algorithms/PVT/libs/rtklib_solver.h b/src/algorithms/PVT/libs/rtklib_solver.h index 7bffa042d..f24a37b2a 100644 --- a/src/algorithms/PVT/libs/rtklib_solver.h +++ b/src/algorithms/PVT/libs/rtklib_solver.h @@ -89,7 +89,7 @@ public: Pvt_Conf conf); ~Rtklib_Solver(); - bool get_PVT(const std::map& gnss_observables_map, bool flag_averaging); + bool get_PVT(const std::map& gnss_observables_map, double kf_update_interval_s); double get_hdop() const override; double get_vdop() const override; From 636f618fbaae68b4a7e11c36386a68d905acfd35 Mon Sep 17 00:00:00 2001 From: miguekf Date: Mon, 10 Jul 2023 15:08:35 +0200 Subject: [PATCH 03/16] [merge] next branches --- src/algorithms/PVT/libs/pvt_kf.cc | 32 +++++++++++++++++++----- src/algorithms/PVT/libs/pvt_kf.h | 5 ++-- src/algorithms/PVT/libs/rtklib_solver.cc | 10 ++++++-- 3 files changed, 37 insertions(+), 10 deletions(-) diff --git a/src/algorithms/PVT/libs/pvt_kf.cc b/src/algorithms/PVT/libs/pvt_kf.cc index 805a53a57..867c0e1dd 100644 --- a/src/algorithms/PVT/libs/pvt_kf.cc +++ b/src/algorithms/PVT/libs/pvt_kf.cc @@ -21,7 +21,8 @@ void Pvt_Kf::init_Kf(const arma::vec& p, const arma::vec& v, - double update_interval_s, + const arma::vec& res_p, + double solver_interval_s, double measures_ecef_pos_sd_m, double measures_ecef_vel_sd_ms, double system_ecef_pos_sd_m, @@ -40,9 +41,9 @@ void Pvt_Kf::init_Kf(const arma::vec& p, d_H = arma::eye(6, 6); // measurement matrix static covariances - d_R = {{pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0, 0.0}, - {0.0, pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0}, - {0.0, 0.0, pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0}, + d_R = {{res_p[0], res_p[3], res_p[5], 0.0, 0.0, 0.0}, + {res_p[3], res_p[1], res_p[4], 0.0, 0.0, 0.0}, + {res_p[4], res_p[5], res_p[2], 0.0, 0.0, 0.0}, {0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, {0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0}, {0.0, 0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0)}}; @@ -92,7 +93,7 @@ void Pvt_Kf::reset_Kf() } -void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v) +void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p) { if (d_initialized) { @@ -104,11 +105,30 @@ void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v) // Measurement update try { + // Measurement residuals + d_R(0,0) = res_p[0]; d_R(0,1) = res_p[3]; d_R(0,2) = res_p[5]; + d_R(1,0) = res_p[3]; d_R(1,1) = res_p[1]; d_R(1,2) = res_p[4]; + d_R(2,0) = res_p[5]; d_R(2,1) = res_p[4]; d_R(2,2) = res_p[2]; + + // Measurement update arma::vec z = arma::join_cols(p, v); arma::mat K = d_P_new_old * d_H.t() * arma::inv(d_H * d_P_new_old * d_H.t() + d_R); // Kalman gain d_x_new_new = d_x_new_old + K * (z - d_H * d_x_new_old); - d_P_new_new = (arma::eye(6, 6) - K * d_H) * d_P_new_old; + arma::mat A = (arma::eye(6, 6) - K * d_H); + d_P_new_new = A * d_P_new_old * A.t() + K * d_R * K.t(); + // Measurement residuals + d_R(0,0) = res_p[0]; d_R(0,1) = res_p[3]; d_R(0,2) = res_p[5]; + d_R(1,0) = res_p[3]; d_R(1,1) = res_p[1]; d_R(1,2) = res_p[4]; + d_R(2,0) = res_p[5]; d_R(2,1) = res_p[4]; d_R(2,2) = res_p[2]; + + // Measurement update + arma::vec z = arma::join_cols(p, v); + arma::mat K = d_P_new_old * d_H.t() * arma::inv(d_H * d_P_new_old * d_H.t() + d_R); // Kalman gain + + d_x_new_new = d_x_new_old + K * (z - d_H * d_x_new_old); + arma::mat A = (arma::eye(6, 6) - K * d_H); + d_P_new_new = A * d_P_new_old * A.t() + K * d_R * K.t(); // prepare data for next KF epoch d_x_old_old = d_x_new_new; diff --git a/src/algorithms/PVT/libs/pvt_kf.h b/src/algorithms/PVT/libs/pvt_kf.h index 204035f21..4d15c45f9 100644 --- a/src/algorithms/PVT/libs/pvt_kf.h +++ b/src/algorithms/PVT/libs/pvt_kf.h @@ -37,13 +37,14 @@ public: virtual ~Pvt_Kf() = default; void init_Kf(const arma::vec& p, const arma::vec& v, - double update_interval_s, + const arma::vec& res_p, + double solver_interval_s, double measures_ecef_pos_sd_m, double measures_ecef_vel_sd_ms, double system_ecef_pos_sd_m, double system_ecef_vel_sd_ms); bool is_initialized() const; - void run_Kf(const arma::vec& p, const arma::vec& v); + void run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p); void get_pv_Kf(arma::vec& p, arma::vec& v) const; void reset_Kf(); diff --git a/src/algorithms/PVT/libs/rtklib_solver.cc b/src/algorithms/PVT/libs/rtklib_solver.cc index 8b9d5b8ee..6fab229f5 100644 --- a/src/algorithms/PVT/libs/rtklib_solver.cc +++ b/src/algorithms/PVT/libs/rtklib_solver.cc @@ -1548,10 +1548,13 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ { arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; + arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], + pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; d_pvt_kf.init_Kf(p, v, - kf_update_interval_s, + res_p, + kf_update_interval_s, d_conf.measures_ecef_pos_sd_m, d_conf.measures_ecef_vel_sd_ms, d_conf.system_ecef_pos_sd_m, @@ -1561,7 +1564,10 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ { arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; - d_pvt_kf.run_Kf(p, v); + arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], + pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; + + d_pvt_kf.run_Kf(p, v, res_p); d_pvt_kf.get_pv_Kf(p, v); pvt_sol.rr[0] = p[0]; // [m] pvt_sol.rr[1] = p[1]; // [m] From fe13fc8f49f4bf5962cbdd1503a23cf8926b56f3 Mon Sep 17 00:00:00 2001 From: "M.A. Gomez" Date: Mon, 10 Jul 2023 15:19:19 +0200 Subject: [PATCH 04/16] [Fix] error --- src/algorithms/PVT/libs/rtklib_solver.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/src/algorithms/PVT/libs/rtklib_solver.cc b/src/algorithms/PVT/libs/rtklib_solver.cc index 39242fdda..6fab229f5 100644 --- a/src/algorithms/PVT/libs/rtklib_solver.cc +++ b/src/algorithms/PVT/libs/rtklib_solver.cc @@ -898,7 +898,6 @@ void Rtklib_Solver::get_current_has_obs_correction(const std::string &signal, ui } -bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_map, double kf_update_interval_s) bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_map, double kf_update_interval_s) { std::map::const_iterator gnss_observables_iter; From 1a81ba7290b8f694a994225fa0b0a5e4224f4ef9 Mon Sep 17 00:00:00 2001 From: miguekf Date: Tue, 11 Jul 2023 20:17:21 +0200 Subject: [PATCH 05/16] [FIX] line duplicity --- src/algorithms/PVT/libs/pvt_kf.cc | 5 ----- 1 file changed, 5 deletions(-) diff --git a/src/algorithms/PVT/libs/pvt_kf.cc b/src/algorithms/PVT/libs/pvt_kf.cc index 187f3998b..ad6875e29 100644 --- a/src/algorithms/PVT/libs/pvt_kf.cc +++ b/src/algorithms/PVT/libs/pvt_kf.cc @@ -110,11 +110,6 @@ void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res d_R(1,0) = res_p[3]; d_R(1,1) = res_p[1]; d_R(1,2) = res_p[4]; d_R(2,0) = res_p[5]; d_R(2,1) = res_p[4]; d_R(2,2) = res_p[2]; - // Measurement residuals - d_R(0,0) = res_p[0]; d_R(0,1) = res_p[3]; d_R(0,2) = res_p[5]; - d_R(1,0) = res_p[3]; d_R(1,1) = res_p[1]; d_R(1,2) = res_p[4]; - d_R(2,0) = res_p[5]; d_R(2,1) = res_p[4]; d_R(2,2) = res_p[2]; - // Measurement update arma::vec z = arma::join_cols(p, v); arma::mat K = d_P_new_old * d_H.t() * arma::inv(d_H * d_P_new_old * d_H.t() + d_R); // Kalman gain From aee1d7a25afb3c9d173aba889b540980ed9fc6b2 Mon Sep 17 00:00:00 2001 From: "M.A. Gomez" Date: Tue, 11 Jul 2023 17:01:46 +0200 Subject: [PATCH 06/16] make clang-format happy --- src/algorithms/PVT/libs/pvt_kf.cc | 12 +++++++++--- src/algorithms/PVT/libs/pvt_kf.h | 1 - src/algorithms/PVT/libs/rtklib_solver.cc | 8 ++++---- 3 files changed, 13 insertions(+), 8 deletions(-) diff --git a/src/algorithms/PVT/libs/pvt_kf.cc b/src/algorithms/PVT/libs/pvt_kf.cc index ad6875e29..9a47732a0 100644 --- a/src/algorithms/PVT/libs/pvt_kf.cc +++ b/src/algorithms/PVT/libs/pvt_kf.cc @@ -106,9 +106,15 @@ void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res try { // Measurement residuals - d_R(0,0) = res_p[0]; d_R(0,1) = res_p[3]; d_R(0,2) = res_p[5]; - d_R(1,0) = res_p[3]; d_R(1,1) = res_p[1]; d_R(1,2) = res_p[4]; - d_R(2,0) = res_p[5]; d_R(2,1) = res_p[4]; d_R(2,2) = res_p[2]; + d_R(0, 0) = res_p[0]; + d_R(0, 1) = res_p[3]; + d_R(0, 2) = res_p[5]; + d_R(1, 0) = res_p[3]; + d_R(1, 1) = res_p[1]; + d_R(1, 2) = res_p[4]; + d_R(2, 0) = res_p[5]; + d_R(2, 1) = res_p[4]; + d_R(2, 2) = res_p[2]; // Measurement update arma::vec z = arma::join_cols(p, v); diff --git a/src/algorithms/PVT/libs/pvt_kf.h b/src/algorithms/PVT/libs/pvt_kf.h index 4be754505..4d15c45f9 100644 --- a/src/algorithms/PVT/libs/pvt_kf.h +++ b/src/algorithms/PVT/libs/pvt_kf.h @@ -67,4 +67,3 @@ private: /** \} */ /** \} */ #endif // GNSS_SDR_Pvt_Kf_H - diff --git a/src/algorithms/PVT/libs/rtklib_solver.cc b/src/algorithms/PVT/libs/rtklib_solver.cc index 6fab229f5..b85d5457c 100644 --- a/src/algorithms/PVT/libs/rtklib_solver.cc +++ b/src/algorithms/PVT/libs/rtklib_solver.cc @@ -1549,12 +1549,12 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], - pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; + pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; d_pvt_kf.init_Kf(p, v, res_p, - kf_update_interval_s, + kf_update_interval_s, d_conf.measures_ecef_pos_sd_m, d_conf.measures_ecef_vel_sd_ms, d_conf.system_ecef_pos_sd_m, @@ -1565,8 +1565,8 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], - pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; - + pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; + d_pvt_kf.run_Kf(p, v, res_p); d_pvt_kf.get_pv_Kf(p, v); pvt_sol.rr[0] = p[0]; // [m] From 643bf5516a922d87a52a4acb48724ea3314b188a Mon Sep 17 00:00:00 2001 From: Javier Arribas Date: Wed, 12 Jul 2023 08:51:15 +0200 Subject: [PATCH 07/16] Adding velocity LS variance and covariance to sol_t structure, not filled --- src/algorithms/libs/rtklib/rtklib.h | 1 + src/algorithms/libs/rtklib/rtklib_pntpos.cc | 2 +- src/algorithms/libs/rtklib/rtklib_rtkpos.cc | 4 ++-- src/algorithms/libs/rtklib/rtklib_rtksvr.cc | 2 +- src/algorithms/libs/rtklib/rtklib_solution.cc | 4 ++-- src/algorithms/libs/rtklib/rtklib_stream.cc | 2 +- 6 files changed, 8 insertions(+), 7 deletions(-) diff --git a/src/algorithms/libs/rtklib/rtklib.h b/src/algorithms/libs/rtklib/rtklib.h index b5658641e..3c259ed3f 100644 --- a/src/algorithms/libs/rtklib/rtklib.h +++ b/src/algorithms/libs/rtklib/rtklib.h @@ -824,6 +824,7 @@ typedef struct float qr[6]; /* position variance/covariance (m^2) */ /* {c_xx,c_yy,c_zz,c_xy,c_yz,c_zx} or */ /* {c_ee,c_nn,c_uu,c_en,c_nu,c_ue} */ + float qvr[6]; /* velocity variance/covariance (ms^2) */ double dtr[6]; /* receiver clock bias to time systems (s) */ unsigned char type; /* type (0:xyz-ecef,1:enu-baseline) */ unsigned char stat; /* solution status (SOLQ_???) */ diff --git a/src/algorithms/libs/rtklib/rtklib_pntpos.cc b/src/algorithms/libs/rtklib/rtklib_pntpos.cc index 8528d9f3d..12f39379f 100644 --- a/src/algorithms/libs/rtklib/rtklib_pntpos.cc +++ b/src/algorithms/libs/rtklib/rtklib_pntpos.cc @@ -827,7 +827,7 @@ int raim_fde(const obsd_t *obs, int n, const double *rs, double *azel, int *vsat, double *resp, char *msg) { obsd_t *obs_e; - sol_t sol_e = {{0, 0}, {}, {}, {}, '0', '0', '0', 0.0, 0.0, 0.0}; + sol_t sol_e = {{0, 0}, {}, {}, {}, {}, '0', '0', '0', 0.0, 0.0, 0.0}; char tstr[32]; char msg_e[128]; double *rs_e; diff --git a/src/algorithms/libs/rtklib/rtklib_rtkpos.cc b/src/algorithms/libs/rtklib/rtklib_rtkpos.cc index 8c31aec6b..828a7cdd2 100644 --- a/src/algorithms/libs/rtklib/rtklib_rtkpos.cc +++ b/src/algorithms/libs/rtklib/rtklib_rtkpos.cc @@ -2650,7 +2650,7 @@ int relpos(rtk_t *rtk, const obsd_t *obs, int nu, int nr, *-----------------------------------------------------------------------------*/ void rtkinit(rtk_t *rtk, const prcopt_t *opt) { - sol_t sol0 = {{0, 0}, {}, {}, {}, '0', '0', '0', 0.0, 0.0, 0.0}; + sol_t sol0 = {{0, 0}, {}, {}, {}, {}, '0', '0', '0', 0.0, 0.0, 0.0}; ambc_t ambc0 = {{{0, 0}, {0, 0}, {0, 0}, {0, 0}}, {}, {}, {}, 0, {}}; ssat_t ssat0 = {0, 0, {0.0}, {0.0}, {0.0}, {'0'}, {'0'}, {'0'}, {'0'}, {'0'}, {}, {}, {}, {}, 0.0, 0.0, 0.0, 0.0, {{{0, 0}}, {{0, 0}}}, {{}, {}}}; int i; @@ -2765,7 +2765,7 @@ void rtkfree(rtk_t *rtk) int rtkpos(rtk_t *rtk, const obsd_t *obs, int n, const nav_t *nav) { prcopt_t *opt = &rtk->opt; - sol_t solb = {{0, 0}, {}, {}, {}, '0', '0', '0', 0.0, 0.0, 0.0}; + sol_t solb = {{0, 0}, {}, {}, {}, {}, '0', '0', '0', 0.0, 0.0, 0.0}; gtime_t time; int i; int nu; diff --git a/src/algorithms/libs/rtklib/rtklib_rtksvr.cc b/src/algorithms/libs/rtklib/rtklib_rtksvr.cc index 22e66eadb..57f1176d8 100644 --- a/src/algorithms/libs/rtklib/rtklib_rtksvr.cc +++ b/src/algorithms/libs/rtklib/rtklib_rtksvr.cc @@ -677,7 +677,7 @@ void *rtksvrthread(void *arg) int rtksvrinit(rtksvr_t *svr) { gtime_t time0 = {0, 0.0}; - sol_t sol0 = {{0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, + sol_t sol0 = {{0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, '0', '0', '0', 0, 0, 0}; eph_t eph0 = {0, -1, -1, 0, 0, 0, 0, 0, {0, 0.0}, {0, 0.0}, {0, 0.0}, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, diff --git a/src/algorithms/libs/rtklib/rtklib_solution.cc b/src/algorithms/libs/rtklib/rtklib_solution.cc index 17ad78ead..240fd6a1a 100644 --- a/src/algorithms/libs/rtklib/rtklib_solution.cc +++ b/src/algorithms/libs/rtklib/rtklib_solution.cc @@ -719,7 +719,7 @@ int decode_solgsi(char *buff, const solopt_t *opt __attribute((unused)), sol_t * /* decode solution position --------------------------------------------------*/ int decode_solpos(char *buff, const solopt_t *opt, sol_t *sol) { - sol_t sol0 = {{0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, '0', '0', '0', 0, 0, 0}; + sol_t sol0 = {{0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, '0', '0', '0', 0, 0, 0}; char *p = buff; trace(4, "decode_solpos: buff=%s\n", buff); @@ -923,7 +923,7 @@ void readsolopt(FILE *fp, solopt_t *opt) int inputsol(unsigned char data, gtime_t ts, gtime_t te, double tint, int qflag, const solopt_t *opt, solbuf_t *solbuf) { - sol_t sol = {{0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, '0', '0', '0', 0, 0, 0}; + sol_t sol = {{0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, '0', '0', '0', 0, 0, 0}; int stat; trace(4, "inputsol: data=0x%02x\n", data); diff --git a/src/algorithms/libs/rtklib/rtklib_stream.cc b/src/algorithms/libs/rtklib/rtklib_stream.cc index e9a29cf3f..303c3197e 100644 --- a/src/algorithms/libs/rtklib/rtklib_stream.cc +++ b/src/algorithms/libs/rtklib/rtklib_stream.cc @@ -2731,7 +2731,7 @@ gtime_t strgettime(stream_t *stream) *-----------------------------------------------------------------------------*/ void strsendnmea(stream_t *stream, const double *pos) { - sol_t sol = {{0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, '0', '0', '0', 0, 0, 0}; + sol_t sol = {{0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, '0', '0', '0', 0, 0, 0}; unsigned char buff[1024]; int i; int n; From dd7b1f9f6ae318ddac362cb34ccdff9762d13487 Mon Sep 17 00:00:00 2001 From: "M.A. Gomez" Date: Wed, 12 Jul 2023 17:26:45 +0200 Subject: [PATCH 08/16] [ADD] estatic_measures_sd flag --- src/algorithms/PVT/adapters/rtklib_pvt.cc | 1975 ++++++------ src/algorithms/PVT/libs/pvt_conf.h | 219 +- src/algorithms/PVT/libs/pvt_kf.cc | 309 +- src/algorithms/PVT/libs/pvt_kf.h | 140 +- src/algorithms/PVT/libs/rtklib_solver.cc | 3559 +++++++++++---------- 5 files changed, 3111 insertions(+), 3091 deletions(-) mode change 100644 => 100755 src/algorithms/PVT/adapters/rtklib_pvt.cc mode change 100644 => 100755 src/algorithms/PVT/libs/pvt_conf.h mode change 100644 => 100755 src/algorithms/PVT/libs/pvt_kf.cc mode change 100644 => 100755 src/algorithms/PVT/libs/pvt_kf.h mode change 100644 => 100755 src/algorithms/PVT/libs/rtklib_solver.cc diff --git a/src/algorithms/PVT/adapters/rtklib_pvt.cc b/src/algorithms/PVT/adapters/rtklib_pvt.cc old mode 100644 new mode 100755 index 9bf6174ab..ad967d953 --- a/src/algorithms/PVT/adapters/rtklib_pvt.cc +++ b/src/algorithms/PVT/adapters/rtklib_pvt.cc @@ -1,987 +1,988 @@ -/*! - * \file rtklib_pvt.cc - * \brief Interface of a Position Velocity and Time computation block - * \author Javier Arribas, 2017. jarribas(at)cttc.es - * - * ----------------------------------------------------------------------------- - * - * GNSS-SDR is a Global Navigation Satellite System software-defined receiver. - * This file is part of GNSS-SDR. - * - * Copyright (C) 2010-2020 (see AUTHORS file for a list of contributors) - * SPDX-License-Identifier: GPL-3.0-or-later - * - * ----------------------------------------------------------------------------- - */ - - -#include "rtklib_pvt.h" -#include "MATH_CONSTANTS.h" // for D2R -#include "configuration_interface.h" // for ConfigurationInterface -#include "galileo_almanac.h" // for Galileo_Almanac -#include "galileo_ephemeris.h" // for Galileo_Ephemeris -#include "gnss_sdr_flags.h" // for FLAGS_RINEX_version -#include "gnss_sdr_string_literals.h" // for std::string_literals -#include "gps_almanac.h" // for Gps_Almanac -#include "gps_ephemeris.h" // for Gps_Ephemeris -#include "pvt_conf.h" // for Pvt_Conf -#include "rtklib_rtkpos.h" // for rtkfree, rtkinit -#include // for LOG -#include // for std::cout -#if USE_STD_COMMON_FACTOR -#include -namespace bc = std; -#else -#if USE_OLD_BOOST_MATH_COMMON_FACTOR -#include -namespace bc = boost::math; -#else -#include -namespace bc = boost::integer; -#endif -#endif - -using namespace std::string_literals; - -Rtklib_Pvt::Rtklib_Pvt(const ConfigurationInterface* configuration, - const std::string& role, - unsigned int in_streams, - unsigned int out_streams) : role_(role), - in_streams_(in_streams), - out_streams_(out_streams) -{ - Pvt_Conf pvt_output_parameters = Pvt_Conf(); - // dump parameters - const std::string default_dump_filename("./pvt.dat"); - const std::string default_nmea_dump_filename("./nmea_pvt.nmea"); - const std::string default_nmea_dump_devname("/dev/tty1"); - const std::string default_rtcm_dump_devname("/dev/pts/1"); - DLOG(INFO) << "role " << role; - pvt_output_parameters.dump = configuration->property(role + ".dump", false); - pvt_output_parameters.dump_filename = configuration->property(role + ".dump_filename", default_dump_filename); - pvt_output_parameters.dump_mat = configuration->property(role + ".dump_mat", true); - - pvt_output_parameters.rtk_trace_level = configuration->property(role + ".rtk_trace_level"s, 0); - - // Flag to postprocess old gnss records (older than 2009) and avoid wrong week rollover - pvt_output_parameters.pre_2009_file = configuration->property("GNSS-SDR.pre_2009_file", false); - - // output rate - pvt_output_parameters.observable_interval_ms = configuration->property("GNSS-SDR.observable_interval_ms", pvt_output_parameters.observable_interval_ms); - - pvt_output_parameters.output_rate_ms = bc::lcm(static_cast(pvt_output_parameters.observable_interval_ms), configuration->property(role + ".output_rate_ms", 500)); - - // display rate - pvt_output_parameters.display_rate_ms = bc::lcm(pvt_output_parameters.output_rate_ms, configuration->property(role + ".display_rate_ms", 500)); - - // PVT KF settings - pvt_output_parameters.enable_pvt_kf = configuration->property(role + ".enable_pvt_kf", false); - pvt_output_parameters.measures_ecef_pos_sd_m = configuration->property(role + ".kf_measures_ecef_pos_sd_m", 1.0); - pvt_output_parameters.measures_ecef_vel_sd_ms = configuration->property(role + ".kf_measures_ecef_vel_sd_ms", 0.1); - pvt_output_parameters.system_ecef_pos_sd_m = configuration->property(role + ".kf_system_ecef_pos_sd_m", 0.01); - pvt_output_parameters.system_ecef_vel_sd_ms = configuration->property(role + ".kf_system_ecef_vel_sd_ms", 0.001); - - // NMEA Printer settings - pvt_output_parameters.flag_nmea_tty_port = configuration->property(role + ".flag_nmea_tty_port", false); - pvt_output_parameters.nmea_dump_filename = configuration->property(role + ".nmea_dump_filename", default_nmea_dump_filename); - pvt_output_parameters.nmea_dump_devname = configuration->property(role + ".nmea_dump_devname", default_nmea_dump_devname); - - // RINEX version - pvt_output_parameters.rinex_version = configuration->property(role + ".rinex_version", 3); - if (FLAGS_RINEX_version == "3.01" || FLAGS_RINEX_version == "3.02" || FLAGS_RINEX_version == "3") - { - pvt_output_parameters.rinex_version = 3; - } - else if (FLAGS_RINEX_version == "2.10" || FLAGS_RINEX_version == "2.11" || FLAGS_RINEX_version == "2") - { - pvt_output_parameters.rinex_version = 2; - } - pvt_output_parameters.rinexobs_rate_ms = bc::lcm(configuration->property(role + ".rinexobs_rate_ms", 1000), pvt_output_parameters.output_rate_ms); - pvt_output_parameters.rinex_name = configuration->property(role + ".rinex_name", std::string("-")); - if (FLAGS_RINEX_name != "-") - { - pvt_output_parameters.rinex_name = FLAGS_RINEX_name; - } - - // RTCM Printer settings - pvt_output_parameters.flag_rtcm_tty_port = configuration->property(role + ".flag_rtcm_tty_port", false); - pvt_output_parameters.rtcm_dump_devname = configuration->property(role + ".rtcm_dump_devname", default_rtcm_dump_devname); - pvt_output_parameters.flag_rtcm_server = configuration->property(role + ".flag_rtcm_server", false); - pvt_output_parameters.rtcm_tcp_port = configuration->property(role + ".rtcm_tcp_port", 2101); - pvt_output_parameters.rtcm_station_id = configuration->property(role + ".rtcm_station_id", 1234); - // RTCM message rates: least common multiple with output_rate_ms - const int rtcm_MT1019_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1019_rate_ms", 5000), pvt_output_parameters.output_rate_ms); - const int rtcm_MT1020_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1020_rate_ms", 5000), pvt_output_parameters.output_rate_ms); - const int rtcm_MT1045_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1045_rate_ms", 5000), pvt_output_parameters.output_rate_ms); - const int rtcm_MSM_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MSM_rate_ms", 1000), pvt_output_parameters.output_rate_ms); - const int rtcm_MT1077_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1077_rate_ms", rtcm_MSM_rate_ms), pvt_output_parameters.output_rate_ms); - const int rtcm_MT1087_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1087_rate_ms", rtcm_MSM_rate_ms), pvt_output_parameters.output_rate_ms); - const int rtcm_MT1097_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1097_rate_ms", rtcm_MSM_rate_ms), pvt_output_parameters.output_rate_ms); - - pvt_output_parameters.rtcm_msg_rate_ms[1019] = rtcm_MT1019_rate_ms; - pvt_output_parameters.rtcm_msg_rate_ms[1020] = rtcm_MT1020_rate_ms; - pvt_output_parameters.rtcm_msg_rate_ms[1045] = rtcm_MT1045_rate_ms; - for (int k = 1071; k < 1078; k++) // All GPS MSM - { - pvt_output_parameters.rtcm_msg_rate_ms[k] = rtcm_MT1077_rate_ms; - } - for (int k = 1081; k < 1088; k++) // All GLONASS MSM - { - pvt_output_parameters.rtcm_msg_rate_ms[k] = rtcm_MT1087_rate_ms; - } - for (int k = 1091; k < 1098; k++) // All Galileo MSM - { - pvt_output_parameters.rtcm_msg_rate_ms[k] = rtcm_MT1097_rate_ms; - } - - // Advanced Nativation Protocol Printer settings - pvt_output_parameters.an_output_enabled = configuration->property(role + ".an_output_enabled", pvt_output_parameters.an_output_enabled); - pvt_output_parameters.an_dump_devname = configuration->property(role + ".an_dump_devname", default_nmea_dump_devname); - if (pvt_output_parameters.an_output_enabled && pvt_output_parameters.flag_nmea_tty_port) - { - if (pvt_output_parameters.nmea_dump_devname == pvt_output_parameters.an_dump_devname) - { - std::cerr << "Warning: NMEA an Advanced Nativation printers set to write to the same serial port.\n" - << "Please make sure that PVT.an_dump_devname and PVT.an_dump_devname are different.\n" - << "Shutting down the NMEA serial output.\n"; - pvt_output_parameters.flag_nmea_tty_port = false; - } - } - if (pvt_output_parameters.an_output_enabled && pvt_output_parameters.flag_rtcm_tty_port) - { - if (pvt_output_parameters.rtcm_dump_devname == pvt_output_parameters.an_dump_devname) - { - std::cerr << "Warning: RTCM an Advanced Nativation printers set to write to the same serial port.\n" - << "Please make sure that PVT.an_dump_devname and .rtcm_dump_devname are different.\n" - << "Shutting down the RTCM serial output.\n"; - pvt_output_parameters.flag_rtcm_tty_port = false; - } - } - - pvt_output_parameters.kml_rate_ms = bc::lcm(configuration->property(role + ".kml_rate_ms", pvt_output_parameters.kml_rate_ms), pvt_output_parameters.output_rate_ms); - pvt_output_parameters.gpx_rate_ms = bc::lcm(configuration->property(role + ".gpx_rate_ms", pvt_output_parameters.gpx_rate_ms), pvt_output_parameters.output_rate_ms); - pvt_output_parameters.geojson_rate_ms = bc::lcm(configuration->property(role + ".geojson_rate_ms", pvt_output_parameters.geojson_rate_ms), pvt_output_parameters.output_rate_ms); - pvt_output_parameters.nmea_rate_ms = bc::lcm(configuration->property(role + ".nmea_rate_ms", pvt_output_parameters.nmea_rate_ms), pvt_output_parameters.output_rate_ms); - pvt_output_parameters.an_rate_ms = configuration->property(role + ".an_rate_ms", pvt_output_parameters.an_rate_ms); - - // Infer the type of receiver - /* - * TYPE | RECEIVER - * 0 | Unknown - * 1 | GPS L1 C/A - * 2 | GPS L2C - * 3 | GPS L5 - * 4 | Galileo E1B - * 5 | Galileo E5a - * 6 | Galileo E5b - * 7 | GPS L1 C/A + GPS L2C - * 8 | GPS L1 C/A + GPS L5 - * 9 | GPS L1 C/A + Galileo E1B - * 10 | GPS L1 C/A + Galileo E5a - * 11 | GPS L1 C/A + Galileo E5b - * 12 | Galileo E1B + GPS L2C - * 13 | Galileo E5a + GPS L5 - * 14 | Galileo E1B + Galileo E5a - * 15 | Galileo E1B + Galileo E5b - * 16 | GPS L2C + GPS L5 - * 17 | GPS L2C + Galileo E5a - * 18 | GPS L2C + Galileo E5b - * 19 | Galileo E5a + Galileo E5b - * 20 | GPS L5 + Galileo E5b - * 21 | GPS L1 C/A + Galileo E1B + GPS L2C - * 22 | GPS L1 C/A + Galileo E1B + GPS L5 - * 23 | GLONASS L1 C/A - * 24 | GLONASS L2 C/A - * 25 | GLONASS L1 C/A + GLONASS L2 C/A - * 26 | GPS L1 C/A + GLONASS L1 C/A - * 27 | Galileo E1B + GLONASS L1 C/A - * 28 | GPS L2C + GLONASS L1 C/A - * 29 | GPS L1 C/A + GLONASS L2 C/A - * 30 | Galileo E1B + GLONASS L2 C/A - * 31 | GPS L2C + GLONASS L2 C/A - * 32 | GPS L1 C/A + Galileo E1B + GPS L5 + Galileo E5a - * 33 | GPS L1 C/A + Galileo E1B + Galileo E5a - * - * Skipped previous values to avoid overlapping - * 100 | Galileo E6B - * 101 | Galileo E1B + Galileo E6B - * 102 | Galileo E5a + Galileo E6B - * 103 | Galileo E5b + Galileo E6B - * 104 | Galileo E1B + Galileo E5a + Galileo E6B - * 105 | Galileo E1B + Galileo E5b + Galileo E6B - * 106 | GPS L1 C/A + Galileo E1B + Galileo E6B - * 107 | GPS L1 C/A + Galileo E6B - * Skipped previous values to avoid overlapping - * 500 | BeiDou B1I - * 501 | BeiDou B1I + GPS L1 C/A - * 502 | BeiDou B1I + Galileo E1B - * 503 | BeiDou B1I + GLONASS L1 C/A - * 504 | BeiDou B1I + GPS L1 C/A + Galileo E1B - * 505 | BeiDou B1I + GPS L1 C/A + GLONASS L1 C/A + Galileo E1B - * 506 | BeiDou B1I + Beidou B3I - * Skipped previous values to avoid overlapping - * 600 | BeiDou B3I - * 601 | BeiDou B3I + GPS L2C - * 602 | BeiDou B3I + GLONASS L2 C/A - * 603 | BeiDou B3I + GPS L2C + GLONASS L2 C/A - * 604 | BeiDou B3I + GPS L1 C/A - * 605 | BeiDou B3I + Galileo E1B - * 606 | BeiDou B3I + GLONASS L1 C/A - * 607 | BeiDou B3I + GPS L1 C/A + Galileo E1B - * 608 | BeiDou B3I + GPS L1 C/A + Galileo E1B + BeiDou B1I - * 609 | BeiDou B3I + GPS L1 C/A + Galileo E1B + GLONASS L1 C/A - * 610 | BeiDou B3I + GPS L1 C/A + Galileo E1B + GLONASS L1 C/A + BeiDou B1I - * - * 1000 | GPS L1 C/A + GPS L2C + GPS L5 - * 1001 | GPS L1 C/A + Galileo E1B + GPS L2C + GPS L5 + Galileo E5a - */ - const int gps_1C_count = configuration->property("Channels_1C.count", 0); - const int gps_2S_count = configuration->property("Channels_2S.count", 0); - const int gps_L5_count = configuration->property("Channels_L5.count", 0); - const int gal_1B_count = configuration->property("Channels_1B.count", 0); - const int gal_E5a_count = configuration->property("Channels_5X.count", 0); - const int gal_E5b_count = configuration->property("Channels_7X.count", 0); - const int gal_E6_count = configuration->property("Channels_E6.count", 0); - const int glo_1G_count = configuration->property("Channels_1G.count", 0); - const int glo_2G_count = configuration->property("Channels_2G.count", 0); - const int bds_B1_count = configuration->property("Channels_B1.count", 0); - const int bds_B3_count = configuration->property("Channels_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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 1; // L1 - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 2; // GPS L2C - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 3; // L5 - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 4; // E1 - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 5; // E5a - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 6; - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 7; // GPS L1 C/A + GPS L2C - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 8; // L1+L5 - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 9; // L1+E1 - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 10; // GPS L1 C/A + Galileo E5a - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 11; - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 12; // Galileo E1B + GPS L2C - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 13; // L5+E5a - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 14; // Galileo E1B + Galileo E5a - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 15; - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 16; // GPS L2C + GPS L5 - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 17; // GPS L2C + Galileo E5a - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 18; // GPS L2C + Galileo E5b - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 19; // Galileo E5a + Galileo E5b - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 20; // GPS L5 + Galileo E5b - } - 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) && (gal_E6_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 - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 22; // GPS L1 C/A + Galileo E1B + GPS L5 - } - 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 23; // GLONASS L1 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 24; // GLONASS L2 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 25; // GLONASS L1 C/A + GLONASS L2 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 26; // GPS L1 C/A + GLONASS L1 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 27; // Galileo E1B + GLONASS L1 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 28; // GPS L2C + GLONASS L1 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 29; // GPS L1 C/A + GLONASS L2 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 30; // Galileo E1B + GLONASS L2 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 31; // GPS L2C + GLONASS L2 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 32; // L1+E1+L5+E5a - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 33; // L1+E1+E5a - } - // Galileo E6 - 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 100; // Galileo E6B - } - 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 101; // Galileo E1B + Galileo E6B - } - 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 102; // Galileo E5a + Galileo E6B - } - 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 103; // Galileo E5b + Galileo E6B - } - 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 104; // Galileo E1B + Galileo E5a + Galileo E6B - } - 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 105; // Galileo E1B + Galileo E5b + Galileo E6B - } - 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 106; // GPS L1 C/A + Galileo E1B + Galileo E6B - } - 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 107; // GPS L1 C/A + Galileo E6B - } - // BeiDou B1I Receiver - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 500; // Beidou B1I - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 501; // Beidou B1I + GPS L1 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 502; // Beidou B1I + Galileo E1B - } - 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 503; // Beidou B1I + GLONASS L1 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 504; // Beidou B1I + GPS L1 C/A + Galileo E1B - } - 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 505; // Beidou B1I + GPS L1 C/A + GLONASS L1 C/A + Galileo E1B - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count != 0)) - { - pvt_output_parameters.type_of_receiver = 506; // Beidou B1I + Beidou B3I - } - // BeiDou B3I Receiver - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count != 0)) - { - pvt_output_parameters.type_of_receiver = 600; // Beidou B3I - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count != 0)) - { - pvt_output_parameters.type_of_receiver = 601; // Beidou B3I + GPS L2C - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count != 0)) - { - pvt_output_parameters.type_of_receiver = 602; // Beidou B3I + GLONASS L2 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count != 0)) - { - pvt_output_parameters.type_of_receiver = 603; // Beidou B3I + GPS L2C + GLONASS L2 C/A - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 1000; // GPS L1 + GPS L2C + GPS L5 - } - 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) - { - pvt_output_parameters.type_of_receiver = 1001; // GPS L1 + Galileo E1B + GPS L2C + GPS L5 + Galileo E5a - } - - // RTKLIB PVT solver options - // Settings 1 - int positioning_mode = -1; - const std::string default_pos_mode("Single"); - const std::string positioning_mode_str = configuration->property(role + ".positioning_mode", default_pos_mode); // (PMODE_XXX) see src/algorithms/libs/rtklib/rtklib.h - if (positioning_mode_str == "Single") - { - positioning_mode = PMODE_SINGLE; - } - if (positioning_mode_str == "Static") - { - positioning_mode = PMODE_STATIC; - } - if (positioning_mode_str == "Kinematic") - { - positioning_mode = PMODE_KINEMA; - } - if (positioning_mode_str == "PPP_Static") - { - positioning_mode = PMODE_PPP_STATIC; - } - if (positioning_mode_str == "PPP_Kinematic") - { - positioning_mode = PMODE_PPP_KINEMA; - } - - if (positioning_mode == -1) - { - // warn user and set the default - std::cout << "WARNING: Bad specification of positioning mode.\n" - << "positioning_mode possible values: Single / Static / Kinematic / PPP_Static / PPP_Kinematic\n" - << "positioning_mode specified value: " << positioning_mode_str << "\n" - << "Setting positioning_mode to Single\n" - << std::flush; - positioning_mode = PMODE_SINGLE; - } - - int num_bands = 0; - - if ((gps_1C_count > 0) || (gal_1B_count > 0) || (glo_1G_count > 0) || (bds_B1_count > 0)) - { - num_bands += 1; - } - if ((gps_2S_count > 0) || (glo_2G_count > 0) || (bds_B3_count > 0)) - { - num_bands += 1; - } - if (gal_E6_count > 0) - { - num_bands += 1; - } - if ((gal_E5a_count > 0) || (gps_L5_count > 0)) - { - num_bands += 1; - } - if (gal_E5b_count > 0) - { - num_bands += 1; - } - if (num_bands > 3) - { - LOG(WARNING) << "Too much bands: The PVT engine can only handle 3 bands, but " << num_bands << " were set"; - num_bands = 3; - } - - int number_of_frequencies = configuration->property(role + ".num_bands", num_bands); /* (1:L1, 2:L1+L2, 3:L1+L2+L5) */ - if ((number_of_frequencies < 1) || (number_of_frequencies > 3)) - { - // warn user and set the default - number_of_frequencies = num_bands; - } - - double elevation_mask = configuration->property(role + ".elevation_mask", 15.0); - if ((elevation_mask < 0.0) || (elevation_mask > 90.0)) - { - // warn user and set the default - LOG(WARNING) << "Erroneous Elevation Mask. Setting to default value of 15.0 degrees"; - elevation_mask = 15.0; - } - - int dynamics_model = configuration->property(role + ".dynamics_model", 0); /* dynamics model (0:none, 1:velocity, 2:accel) */ - if ((dynamics_model < 0) || (dynamics_model > 2)) - { - // warn user and set the default - LOG(WARNING) << "Erroneous Dynamics Model configuration. Setting to default value of (0:none)"; - dynamics_model = 0; - } - - const std::string default_iono_model("OFF"); - const std::string iono_model_str = configuration->property(role + ".iono_model", default_iono_model); /* (IONOOPT_XXX) see src/algorithms/libs/rtklib/rtklib.h */ - int iono_model = -1; - if (iono_model_str == "OFF") - { - iono_model = IONOOPT_OFF; - } - if (iono_model_str == "Broadcast") - { - iono_model = IONOOPT_BRDC; - } - if (iono_model_str == "SBAS") - { - iono_model = IONOOPT_SBAS; - } - if (iono_model_str == "Iono-Free-LC") - { - iono_model = IONOOPT_IFLC; - } - if (iono_model_str == "Estimate_STEC") - { - iono_model = IONOOPT_EST; - } - if (iono_model_str == "IONEX") - { - iono_model = IONOOPT_TEC; - } - if (iono_model == -1) - { - // warn user and set the default - std::cout << "WARNING: Bad specification of ionospheric model.\n" - << "iono_model possible values: OFF / Broadcast / SBAS / Iono-Free-LC / Estimate_STEC / IONEX\n" - << "iono_model specified value: " << iono_model_str << "\n" - << "Setting iono_model to OFF\n" - << std::flush; - iono_model = IONOOPT_OFF; /* 0: ionosphere option: correction off */ - } - - const std::string default_trop_model("OFF"); - int trop_model = -1; - const std::string trop_model_str = configuration->property(role + ".trop_model", default_trop_model); /* (TROPOPT_XXX) see src/algorithms/libs/rtklib/rtklib.h */ - if (trop_model_str == "OFF") - { - trop_model = TROPOPT_OFF; - } - if (trop_model_str == "Saastamoinen") - { - trop_model = TROPOPT_SAAS; - } - if (trop_model_str == "SBAS") - { - trop_model = TROPOPT_SBAS; - } - if (trop_model_str == "Estimate_ZTD") - { - trop_model = TROPOPT_EST; - } - if (trop_model_str == "Estimate_ZTD_Grad") - { - trop_model = TROPOPT_ESTG; - } - if (trop_model == -1) - { - // warn user and set the default - std::cout << "WARNING: Bad specification of tropospheric model.\n" - << "trop_model possible values: OFF / Saastamoinen / SBAS / Estimate_ZTD / Estimate_ZTD_Grad\n" - << "trop_model specified value: " << trop_model_str << "\n" - << "Setting trop_model to OFF\n" - << std::flush; - trop_model = TROPOPT_OFF; - } - - /* RTKLIB positioning options */ - int sat_PCV = 0; /* Set whether the satellite antenna PCV (phase center variation) model is used or not. This feature requires a Satellite Antenna PCV File. */ - int rec_PCV = 0; /* Set whether the receiver antenna PCV (phase center variation) model is used or not. This feature requires a Receiver Antenna PCV File. */ - - /* Set whether the phase windup correction for PPP modes is applied or not. Only applicable to PPP‐* modes.*/ - const int phwindup = configuration->property(role + ".phwindup", 0); - - /* Set whether the GPS Block IIA satellites in eclipse are excluded or not. - The eclipsing Block IIA satellites often degrade the PPP solutions due to unpredicted behavior of yaw‐attitude. Only applicable to PPP‐* modes.*/ - const int reject_GPS_IIA = configuration->property(role + ".reject_GPS_IIA", 0); - - /* Set whether RAIM (receiver autonomous integrity monitoring) FDE (fault detection and exclusion) feature is enabled or not. - In case of RAIM FDE enabled, a satellite is excluded if SSE (sum of squared errors) of residuals is over a threshold. - The excluded satellite is selected to indicate the minimum SSE. */ - const int raim_fde = configuration->property(role + ".raim_fde", 0); - - const int earth_tide = configuration->property(role + ".earth_tide", 0); - - int nsys = 0; - if ((gps_1C_count > 0) || (gps_2S_count > 0) || (gps_L5_count > 0)) - { - nsys += SYS_GPS; - } - if ((gal_1B_count > 0) || (gal_E5a_count > 0) || (gal_E5b_count > 0) || (gal_E6_count > 0)) - { - nsys += SYS_GAL; - } - if ((glo_1G_count > 0) || (glo_2G_count > 0)) - { - nsys += SYS_GLO; - } - if ((bds_B1_count > 0) || (bds_B3_count > 0)) - { - nsys += SYS_BDS; - } - - int navigation_system = configuration->property(role + ".navigation_system", nsys); /* (SYS_XXX) see src/algorithms/libs/rtklib/rtklib.h */ - if ((navigation_system < 1) || (navigation_system > 255)) /* GPS: 1 SBAS: 2 GPS+SBAS: 3 Galileo: 8 Galileo+GPS: 9 GPS+SBAS+Galileo: 11 All: 255 */ - { - // warn user and set the default - LOG(WARNING) << "Erroneous Navigation System. Setting to default value of (0:none)"; - navigation_system = nsys; - } - - // Settings 2 - const std::string default_gps_ar("Continuous"); - const std::string integer_ambiguity_resolution_gps_str = configuration->property(role + ".AR_GPS", default_gps_ar); /* Integer Ambiguity Resolution mode for GPS (0:off,1:continuous,2:instantaneous,3:fix and hold,4:ppp-ar) */ - int integer_ambiguity_resolution_gps = -1; - if (integer_ambiguity_resolution_gps_str == "OFF") - { - integer_ambiguity_resolution_gps = ARMODE_OFF; - } - if (integer_ambiguity_resolution_gps_str == "Continuous") - { - integer_ambiguity_resolution_gps = ARMODE_CONT; - } - if (integer_ambiguity_resolution_gps_str == "Instantaneous") - { - integer_ambiguity_resolution_gps = ARMODE_INST; - } - if (integer_ambiguity_resolution_gps_str == "Fix-and-Hold") - { - integer_ambiguity_resolution_gps = ARMODE_FIXHOLD; - } - if (integer_ambiguity_resolution_gps_str == "PPP-AR") - { - integer_ambiguity_resolution_gps = ARMODE_PPPAR; - } - if (integer_ambiguity_resolution_gps == -1) - { - // warn user and set the default - std::cout << "WARNING: Bad specification of GPS ambiguity resolution method.\n" - << "AR_GPS possible values: OFF / Continuous / Instantaneous / Fix-and-Hold / PPP-AR\n" - << "AR_GPS specified value: " << integer_ambiguity_resolution_gps_str << "\n" - << "Setting AR_GPS to OFF\n" - << std::flush; - integer_ambiguity_resolution_gps = ARMODE_OFF; - } - - int integer_ambiguity_resolution_glo = configuration->property(role + ".AR_GLO", 1); /* Integer Ambiguity Resolution mode for GLONASS (0:off,1:on,2:auto cal,3:ext cal) */ - if ((integer_ambiguity_resolution_glo < 0) || (integer_ambiguity_resolution_glo > 3)) - { - // warn user and set the default - LOG(WARNING) << "Erroneous Integer Ambiguity Resolution for GLONASS . Setting to default value of (1:on)"; - integer_ambiguity_resolution_glo = 1; - } - - int integer_ambiguity_resolution_bds = configuration->property(role + ".AR_DBS", 1); /* Integer Ambiguity Resolution mode for BEIDOU (0:off,1:on) */ - if ((integer_ambiguity_resolution_bds < 0) || (integer_ambiguity_resolution_bds > 1)) - { - // warn user and set the default - LOG(WARNING) << "Erroneous Integer Ambiguity Resolution for BEIDOU . Setting to default value of (1:on)"; - integer_ambiguity_resolution_bds = 1; - } - - const double min_ratio_to_fix_ambiguity = configuration->property(role + ".min_ratio_to_fix_ambiguity", 3.0); /* Set the integer ambiguity validation threshold for ratio‐test, - which uses the ratio of squared residuals of the best integer vector to the second‐best vector. */ - - const int min_lock_to_fix_ambiguity = configuration->property(role + ".min_lock_to_fix_ambiguity", 0); /* Set the minimum lock count to fix integer ambiguity.FLAGS_RINEX_version. - If the lock count is less than the value, the ambiguity is excluded from the fixed integer vector. */ - - const double min_elevation_to_fix_ambiguity = configuration->property(role + ".min_elevation_to_fix_ambiguity", 0.0); /* Set the minimum elevation (deg) to fix integer ambiguity. - If the elevation of the satellite is less than the value, the ambiguity is excluded from the fixed integer vector. */ - - const int outage_reset_ambiguity = configuration->property(role + ".outage_reset_ambiguity", 5); /* Set the outage count to reset ambiguity. If the data outage count is over the value, the estimated ambiguity is reset to the initial value. */ - - const double slip_threshold = configuration->property(role + ".slip_threshold", 0.05); /* set the cycle‐slip threshold (m) of geometry‐free LC carrier‐phase difference between epochs */ - - const double threshold_reject_gdop = configuration->property(role + ".threshold_reject_gdop", 30.0); /* reject threshold of GDOP. If the GDOP is over the value, the observable is excluded for the estimation process as an outlier. */ - - const double threshold_reject_innovation = configuration->property(role + ".threshold_reject_innovation", 30.0); /* reject threshold of innovation (m). If the innovation is over the value, the observable is excluded for the estimation process as an outlier. */ - - const int number_filter_iter = configuration->property(role + ".number_filter_iter", 1); /* Set the number of iteration in the measurement update of the estimation filter. - If the baseline length is very short like 1 m, the iteration may be effective to handle - the nonlinearity of measurement equation. */ - - // Statistics - const double bias_0 = configuration->property(role + ".bias_0", 30.0); - - const double iono_0 = configuration->property(role + ".iono_0", 0.03); - - const double trop_0 = configuration->property(role + ".trop_0", 0.3); - - const double sigma_bias = configuration->property(role + ".sigma_bias", 1e-4); /* Set the process noise standard deviation of carrier‐phase - bias (ambiguity) (cycle/sqrt(s)) */ - - const double sigma_iono = configuration->property(role + ".sigma_iono", 1e-3); /* Set the process noise standard deviation of vertical ionospheric delay per 10 km baseline (m/sqrt(s)). */ - - const double sigma_trop = configuration->property(role + ".sigma_trop", 1e-4); /* Set the process noise standard deviation of zenith tropospheric delay (m/sqrt(s)). */ - - const double sigma_acch = configuration->property(role + ".sigma_acch", 1e-1); /* Set the process noise standard deviation of the receiver acceleration as - the horizontal component. (m/s2/sqrt(s)). If Receiver Dynamics is set to OFF, they are not used. */ - - const double sigma_accv = configuration->property(role + ".sigma_accv", 1e-2); /* Set the process noise standard deviation of the receiver acceleration as - the vertical component. (m/s2/sqrt(s)). If Receiver Dynamics is set to OFF, they are not used. */ - - const double sigma_pos = configuration->property(role + ".sigma_pos", 0.0); - - const double code_phase_error_ratio_l1 = configuration->property(role + ".code_phase_error_ratio_l1", 100.0); - const double code_phase_error_ratio_l2 = configuration->property(role + ".code_phase_error_ratio_l2", 100.0); - const double code_phase_error_ratio_l5 = configuration->property(role + ".code_phase_error_ratio_l5", 100.0); - const double carrier_phase_error_factor_a = configuration->property(role + ".carrier_phase_error_factor_a", 0.003); - const double carrier_phase_error_factor_b = configuration->property(role + ".carrier_phase_error_factor_b", 0.003); - - const bool bancroft_init = configuration->property(role + ".bancroft_init", true); - - snrmask_t snrmask = {{}, {{}, {}}}; - - prcopt_t rtklib_configuration_options = { - positioning_mode, /* positioning mode (PMODE_XXX) see src/algorithms/libs/rtklib/rtklib.h */ - 0, /* solution type (0:forward,1:backward,2:combined) */ - number_of_frequencies, /* number of frequencies (1:L1, 2:L1+L2, 3:L1+L2+L5)*/ - navigation_system, /* navigation system */ - elevation_mask * D2R, /* elevation mask angle (degrees) */ - snrmask, /* snrmask_t snrmask SNR mask */ - 0, /* satellite ephemeris/clock (EPHOPT_XXX) */ - integer_ambiguity_resolution_gps, /* AR mode (0:off,1:continuous,2:instantaneous,3:fix and hold,4:ppp-ar) */ - integer_ambiguity_resolution_glo, /* GLONASS AR mode (0:off,1:on,2:auto cal,3:ext cal) */ - integer_ambiguity_resolution_bds, /* BeiDou AR mode (0:off,1:on) */ - outage_reset_ambiguity, /* obs outage count to reset bias */ - min_lock_to_fix_ambiguity, /* min lock count to fix ambiguity */ - 10, /* min fix count to hold ambiguity */ - 1, /* max iteration to resolve ambiguity */ - iono_model, /* ionosphere option (IONOOPT_XXX) */ - trop_model, /* troposphere option (TROPOPT_XXX) */ - dynamics_model, /* dynamics model (0:none, 1:velocity, 2:accel) */ - earth_tide, /* earth tide correction (0:off,1:solid,2:solid+otl+pole) */ - number_filter_iter, /* number of filter iteration */ - 0, /* code smoothing window size (0:none) */ - 0, /* interpolate reference obs (for post mission) */ - 0, /* sbssat_t sbssat SBAS correction options */ - 0, /* sbsion_t sbsion[MAXBAND+1] SBAS satellite selection (0:all) */ - 0, /* rover position for fixed mode */ - 0, /* base position for relative mode */ - /* 0:pos in prcopt, 1:average of single pos, */ - /* 2:read from file, 3:rinex header, 4:rtcm pos */ - {code_phase_error_ratio_l1, code_phase_error_ratio_l2, code_phase_error_ratio_l5}, /* eratio[NFREQ] code/phase error ratio */ - {100.0, carrier_phase_error_factor_a, carrier_phase_error_factor_b, 0.0, 1.0}, /* err[5]: measurement error factor [0]:reserved, [1-3]:error factor a/b/c of phase (m) , [4]:doppler frequency (hz) */ - {bias_0, iono_0, trop_0}, /* std[3]: initial-state std [0]bias,[1]iono [2]trop*/ - {sigma_bias, sigma_iono, sigma_trop, sigma_acch, sigma_accv, sigma_pos}, /* prn[6] process-noise std */ - 5e-12, /* sclkstab: satellite clock stability (sec/sec) */ - {min_ratio_to_fix_ambiguity, 0.9999, 0.25, 0.1, 0.05, 0.0, 0.0, 0.0}, /* thresar[8]: AR validation threshold */ - min_elevation_to_fix_ambiguity, /* elevation mask of AR for rising satellite (deg) */ - 0.0, /* elevation mask to hold ambiguity (deg) */ - slip_threshold, /* slip threshold of geometry-free phase (m) */ - 30.0, /* max difference of time (sec) */ - threshold_reject_innovation, /* reject threshold of innovation (m) */ - threshold_reject_gdop, /* reject threshold of gdop */ - {}, /* double baseline[2] baseline length constraint {const,sigma} (m) */ - {}, /* double ru[3] rover position for fixed mode {x,y,z} (ecef) (m) */ - {}, /* double rb[3] base position for relative mode {x,y,z} (ecef) (m) */ - {"", ""}, /* char anttype[2][MAXANT] antenna types {rover,base} */ - {{}, {}}, /* double antdel[2][3] antenna delta {{rov_e,rov_n,rov_u},{ref_e,ref_n,ref_u}} */ - {}, /* pcv_t pcvr[2] receiver antenna parameters {rov,base} */ - {}, /* unsigned char exsats[MAXSAT] excluded satellites (1:excluded, 2:included) */ - 0, /* max averaging epoches */ - 0, /* initialize by restart */ - 1, /* output single by dgps/float/fix/ppp outage */ - {"", ""}, /* char rnxopt[2][256] rinex options {rover,base} */ - {sat_PCV, rec_PCV, phwindup, reject_GPS_IIA, raim_fde}, /* posopt[6] positioning options [0]: satellite and receiver antenna PCV model; [1]: interpolate antenna parameters; [2]: apply phase wind-up correction for PPP modes; [3]: exclude measurements of GPS Block IIA satellites satellite [4]: RAIM FDE (fault detection and exclusion) [5]: handle day-boundary clock jump */ - 0, /* solution sync mode (0:off,1:on) */ - {{}, {}}, /* odisp[2][6*11] ocean tide loading parameters {rov,base} */ - {{}, {{}, {}}, {{}, {}}, {}, {}}, /* exterr_t exterr extended receiver error model */ - 0, /* disable L2-AR */ - {}, /* char pppopt[256] ppp option "-GAP_RESION=" default gap to reset iono parameters (ep) */ - bancroft_init /* enable Bancroft initialization for the first iteration of the PVT computation, useful in some geometries */ - }; - - rtkinit(&rtk, &rtklib_configuration_options); - - // Outputs - const bool default_output_enabled = configuration->property(role + ".output_enabled", true); - pvt_output_parameters.output_enabled = default_output_enabled; - pvt_output_parameters.rinex_output_enabled = configuration->property(role + ".rinex_output_enabled", default_output_enabled); - pvt_output_parameters.gpx_output_enabled = configuration->property(role + ".gpx_output_enabled", default_output_enabled); - pvt_output_parameters.geojson_output_enabled = configuration->property(role + ".geojson_output_enabled", default_output_enabled); - pvt_output_parameters.kml_output_enabled = configuration->property(role + ".kml_output_enabled", default_output_enabled); - pvt_output_parameters.xml_output_enabled = configuration->property(role + ".xml_output_enabled", default_output_enabled); - pvt_output_parameters.nmea_output_file_enabled = configuration->property(role + ".nmea_output_file_enabled", default_output_enabled); - pvt_output_parameters.rtcm_output_file_enabled = configuration->property(role + ".rtcm_output_file_enabled", false); - - const std::string default_output_path = configuration->property(role + ".output_path", std::string(".")); - pvt_output_parameters.output_path = default_output_path; - pvt_output_parameters.rinex_output_path = configuration->property(role + ".rinex_output_path", default_output_path); - pvt_output_parameters.gpx_output_path = configuration->property(role + ".gpx_output_path", default_output_path); - pvt_output_parameters.geojson_output_path = configuration->property(role + ".geojson_output_path", default_output_path); - pvt_output_parameters.kml_output_path = configuration->property(role + ".kml_output_path", default_output_path); - pvt_output_parameters.xml_output_path = configuration->property(role + ".xml_output_path", default_output_path); - pvt_output_parameters.nmea_output_file_path = configuration->property(role + ".nmea_output_file_path", default_output_path); - pvt_output_parameters.rtcm_output_file_path = configuration->property(role + ".rtcm_output_file_path", default_output_path); - - // Read PVT MONITOR Configuration - pvt_output_parameters.monitor_enabled = configuration->property(role + ".enable_monitor", false); - pvt_output_parameters.udp_addresses = configuration->property(role + ".monitor_client_addresses", std::string("127.0.0.1")); - pvt_output_parameters.udp_port = configuration->property(role + ".monitor_udp_port", 1234); - pvt_output_parameters.protobuf_enabled = configuration->property(role + ".enable_protobuf", true); - if (configuration->property("Monitor.enable_protobuf", false) == true) - { - pvt_output_parameters.protobuf_enabled = true; - } - - // Read EPHEMERIS MONITOR Configuration - pvt_output_parameters.monitor_ephemeris_enabled = configuration->property(role + ".enable_monitor_ephemeris", false); - pvt_output_parameters.udp_eph_addresses = configuration->property(role + ".monitor_ephemeris_client_addresses", std::string("127.0.0.1")); - pvt_output_parameters.udp_eph_port = configuration->property(role + ".monitor_ephemeris_udp_port", 1234); - - // Show time in local zone - pvt_output_parameters.show_local_time_zone = configuration->property(role + ".show_local_time_zone", false); - - // Enable or disable rx clock correction in observables - pvt_output_parameters.enable_rx_clock_correction = configuration->property(role + ".enable_rx_clock_correction", false); - - // Set maximum clock offset allowed if pvt_output_parameters.enable_rx_clock_correction = false - pvt_output_parameters.max_obs_block_rx_clock_offset_ms = configuration->property(role + ".max_clock_offset_ms", pvt_output_parameters.max_obs_block_rx_clock_offset_ms); - - // Source timetag - pvt_output_parameters.log_source_timetag = configuration->property(role + ".log_timetag", pvt_output_parameters.log_source_timetag); - pvt_output_parameters.log_source_timetag_file = configuration->property(role + ".log_source_timetag_file", pvt_output_parameters.log_source_timetag_file); - - // Use E6 for PVT - pvt_output_parameters.use_e6_for_pvt = configuration->property(role + ".use_e6_for_pvt", pvt_output_parameters.use_e6_for_pvt); - pvt_output_parameters.use_has_corrections = configuration->property(role + ".use_has_corrections", pvt_output_parameters.use_has_corrections); - - // Use unhealthy satellites - pvt_output_parameters.use_unhealthy_sats = configuration->property(role + ".use_unhealthy_sats", pvt_output_parameters.use_unhealthy_sats); - - // make PVT object - pvt_ = rtklib_make_pvt_gs(in_streams_, pvt_output_parameters, rtk); - DLOG(INFO) << "pvt(" << pvt_->unique_id() << ")"; - if (out_streams_ > 0) - { - LOG(ERROR) << "The PVT block does not have an output stream"; - } -} - - -Rtklib_Pvt::~Rtklib_Pvt() -{ - DLOG(INFO) << "PVT adapter destructor called."; - rtkfree(&rtk); -} - - -bool Rtklib_Pvt::get_latest_PVT(double* longitude_deg, - double* latitude_deg, - double* height_m, - double* ground_speed_kmh, - double* course_over_ground_deg, - time_t* UTC_time) -{ - return pvt_->get_latest_PVT(longitude_deg, - latitude_deg, - height_m, - ground_speed_kmh, - course_over_ground_deg, - UTC_time); -} - - -void Rtklib_Pvt::clear_ephemeris() -{ - pvt_->clear_ephemeris(); -} - - -std::map Rtklib_Pvt::get_gps_ephemeris() const -{ - return pvt_->get_gps_ephemeris_map(); -} - - -std::map Rtklib_Pvt::get_galileo_ephemeris() const -{ - return pvt_->get_galileo_ephemeris_map(); -} - - -std::map Rtklib_Pvt::get_gps_almanac() const -{ - return pvt_->get_gps_almanac_map(); -} - - -std::map Rtklib_Pvt::get_galileo_almanac() const -{ - return pvt_->get_galileo_almanac_map(); -} - - -void Rtklib_Pvt::connect(gr::top_block_sptr top_block) -{ - if (top_block) - { /* top_block is not null */ - }; - // Nothing to connect internally - DLOG(INFO) << "nothing to connect internally"; -} - - -void Rtklib_Pvt::disconnect(gr::top_block_sptr top_block) -{ - if (top_block) - { /* top_block is not null */ - }; - // Nothing to disconnect -} - - -gr::basic_block_sptr Rtklib_Pvt::get_left_block() -{ - return pvt_; -} - - -gr::basic_block_sptr Rtklib_Pvt::get_right_block() -{ - return nullptr; // this is a sink, nothing downstream -} +/*! + * \file rtklib_pvt.cc + * \brief Interface of a Position Velocity and Time computation block + * \author Javier Arribas, 2017. jarribas(at)cttc.es + * + * ----------------------------------------------------------------------------- + * + * GNSS-SDR is a Global Navigation Satellite System software-defined receiver. + * This file is part of GNSS-SDR. + * + * Copyright (C) 2010-2020 (see AUTHORS file for a list of contributors) + * SPDX-License-Identifier: GPL-3.0-or-later + * + * ----------------------------------------------------------------------------- + */ + + +#include "rtklib_pvt.h" +#include "MATH_CONSTANTS.h" // for D2R +#include "configuration_interface.h" // for ConfigurationInterface +#include "galileo_almanac.h" // for Galileo_Almanac +#include "galileo_ephemeris.h" // for Galileo_Ephemeris +#include "gnss_sdr_flags.h" // for FLAGS_RINEX_version +#include "gnss_sdr_string_literals.h" // for std::string_literals +#include "gps_almanac.h" // for Gps_Almanac +#include "gps_ephemeris.h" // for Gps_Ephemeris +#include "pvt_conf.h" // for Pvt_Conf +#include "rtklib_rtkpos.h" // for rtkfree, rtkinit +#include // for LOG +#include // for std::cout +#if USE_STD_COMMON_FACTOR +#include +namespace bc = std; +#else +#if USE_OLD_BOOST_MATH_COMMON_FACTOR +#include +namespace bc = boost::math; +#else +#include +namespace bc = boost::integer; +#endif +#endif + +using namespace std::string_literals; + +Rtklib_Pvt::Rtklib_Pvt(const ConfigurationInterface* configuration, + const std::string& role, + unsigned int in_streams, + unsigned int out_streams) : role_(role), + in_streams_(in_streams), + out_streams_(out_streams) +{ + Pvt_Conf pvt_output_parameters = Pvt_Conf(); + // dump parameters + const std::string default_dump_filename("./pvt.dat"); + const std::string default_nmea_dump_filename("./nmea_pvt.nmea"); + const std::string default_nmea_dump_devname("/dev/tty1"); + const std::string default_rtcm_dump_devname("/dev/pts/1"); + DLOG(INFO) << "role " << role; + pvt_output_parameters.dump = configuration->property(role + ".dump", false); + pvt_output_parameters.dump_filename = configuration->property(role + ".dump_filename", default_dump_filename); + pvt_output_parameters.dump_mat = configuration->property(role + ".dump_mat", true); + + pvt_output_parameters.rtk_trace_level = configuration->property(role + ".rtk_trace_level"s, 0); + + // Flag to postprocess old gnss records (older than 2009) and avoid wrong week rollover + pvt_output_parameters.pre_2009_file = configuration->property("GNSS-SDR.pre_2009_file", false); + + // output rate + pvt_output_parameters.observable_interval_ms = configuration->property("GNSS-SDR.observable_interval_ms", pvt_output_parameters.observable_interval_ms); + + pvt_output_parameters.output_rate_ms = bc::lcm(static_cast(pvt_output_parameters.observable_interval_ms), configuration->property(role + ".output_rate_ms", 500)); + + // display rate + pvt_output_parameters.display_rate_ms = bc::lcm(pvt_output_parameters.output_rate_ms, configuration->property(role + ".display_rate_ms", 500)); + + // PVT KF settings + pvt_output_parameters.enable_pvt_kf = configuration->property(role + ".enable_pvt_kf", false); + pvt_output_parameters.estatic_measures_sd = configuration->property(role + ".estatic_measures_sd", false); + pvt_output_parameters.measures_ecef_pos_sd_m = configuration->property(role + ".kf_measures_ecef_pos_sd_m", 1.0); + pvt_output_parameters.measures_ecef_vel_sd_ms = configuration->property(role + ".kf_measures_ecef_vel_sd_ms", 0.1); + pvt_output_parameters.system_ecef_pos_sd_m = configuration->property(role + ".kf_system_ecef_pos_sd_m", 0.01); + pvt_output_parameters.system_ecef_vel_sd_ms = configuration->property(role + ".kf_system_ecef_vel_sd_ms", 0.001); + + // NMEA Printer settings + pvt_output_parameters.flag_nmea_tty_port = configuration->property(role + ".flag_nmea_tty_port", false); + pvt_output_parameters.nmea_dump_filename = configuration->property(role + ".nmea_dump_filename", default_nmea_dump_filename); + pvt_output_parameters.nmea_dump_devname = configuration->property(role + ".nmea_dump_devname", default_nmea_dump_devname); + + // RINEX version + pvt_output_parameters.rinex_version = configuration->property(role + ".rinex_version", 3); + if (FLAGS_RINEX_version == "3.01" || FLAGS_RINEX_version == "3.02" || FLAGS_RINEX_version == "3") + { + pvt_output_parameters.rinex_version = 3; + } + else if (FLAGS_RINEX_version == "2.10" || FLAGS_RINEX_version == "2.11" || FLAGS_RINEX_version == "2") + { + pvt_output_parameters.rinex_version = 2; + } + pvt_output_parameters.rinexobs_rate_ms = bc::lcm(configuration->property(role + ".rinexobs_rate_ms", 1000), pvt_output_parameters.output_rate_ms); + pvt_output_parameters.rinex_name = configuration->property(role + ".rinex_name", std::string("-")); + if (FLAGS_RINEX_name != "-") + { + pvt_output_parameters.rinex_name = FLAGS_RINEX_name; + } + + // RTCM Printer settings + pvt_output_parameters.flag_rtcm_tty_port = configuration->property(role + ".flag_rtcm_tty_port", false); + pvt_output_parameters.rtcm_dump_devname = configuration->property(role + ".rtcm_dump_devname", default_rtcm_dump_devname); + pvt_output_parameters.flag_rtcm_server = configuration->property(role + ".flag_rtcm_server", false); + pvt_output_parameters.rtcm_tcp_port = configuration->property(role + ".rtcm_tcp_port", 2101); + pvt_output_parameters.rtcm_station_id = configuration->property(role + ".rtcm_station_id", 1234); + // RTCM message rates: least common multiple with output_rate_ms + const int rtcm_MT1019_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1019_rate_ms", 5000), pvt_output_parameters.output_rate_ms); + const int rtcm_MT1020_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1020_rate_ms", 5000), pvt_output_parameters.output_rate_ms); + const int rtcm_MT1045_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1045_rate_ms", 5000), pvt_output_parameters.output_rate_ms); + const int rtcm_MSM_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MSM_rate_ms", 1000), pvt_output_parameters.output_rate_ms); + const int rtcm_MT1077_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1077_rate_ms", rtcm_MSM_rate_ms), pvt_output_parameters.output_rate_ms); + const int rtcm_MT1087_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1087_rate_ms", rtcm_MSM_rate_ms), pvt_output_parameters.output_rate_ms); + const int rtcm_MT1097_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1097_rate_ms", rtcm_MSM_rate_ms), pvt_output_parameters.output_rate_ms); + + pvt_output_parameters.rtcm_msg_rate_ms[1019] = rtcm_MT1019_rate_ms; + pvt_output_parameters.rtcm_msg_rate_ms[1020] = rtcm_MT1020_rate_ms; + pvt_output_parameters.rtcm_msg_rate_ms[1045] = rtcm_MT1045_rate_ms; + for (int k = 1071; k < 1078; k++) // All GPS MSM + { + pvt_output_parameters.rtcm_msg_rate_ms[k] = rtcm_MT1077_rate_ms; + } + for (int k = 1081; k < 1088; k++) // All GLONASS MSM + { + pvt_output_parameters.rtcm_msg_rate_ms[k] = rtcm_MT1087_rate_ms; + } + for (int k = 1091; k < 1098; k++) // All Galileo MSM + { + pvt_output_parameters.rtcm_msg_rate_ms[k] = rtcm_MT1097_rate_ms; + } + + // Advanced Nativation Protocol Printer settings + pvt_output_parameters.an_output_enabled = configuration->property(role + ".an_output_enabled", pvt_output_parameters.an_output_enabled); + pvt_output_parameters.an_dump_devname = configuration->property(role + ".an_dump_devname", default_nmea_dump_devname); + if (pvt_output_parameters.an_output_enabled && pvt_output_parameters.flag_nmea_tty_port) + { + if (pvt_output_parameters.nmea_dump_devname == pvt_output_parameters.an_dump_devname) + { + std::cerr << "Warning: NMEA an Advanced Nativation printers set to write to the same serial port.\n" + << "Please make sure that PVT.an_dump_devname and PVT.an_dump_devname are different.\n" + << "Shutting down the NMEA serial output.\n"; + pvt_output_parameters.flag_nmea_tty_port = false; + } + } + if (pvt_output_parameters.an_output_enabled && pvt_output_parameters.flag_rtcm_tty_port) + { + if (pvt_output_parameters.rtcm_dump_devname == pvt_output_parameters.an_dump_devname) + { + std::cerr << "Warning: RTCM an Advanced Nativation printers set to write to the same serial port.\n" + << "Please make sure that PVT.an_dump_devname and .rtcm_dump_devname are different.\n" + << "Shutting down the RTCM serial output.\n"; + pvt_output_parameters.flag_rtcm_tty_port = false; + } + } + + pvt_output_parameters.kml_rate_ms = bc::lcm(configuration->property(role + ".kml_rate_ms", pvt_output_parameters.kml_rate_ms), pvt_output_parameters.output_rate_ms); + pvt_output_parameters.gpx_rate_ms = bc::lcm(configuration->property(role + ".gpx_rate_ms", pvt_output_parameters.gpx_rate_ms), pvt_output_parameters.output_rate_ms); + pvt_output_parameters.geojson_rate_ms = bc::lcm(configuration->property(role + ".geojson_rate_ms", pvt_output_parameters.geojson_rate_ms), pvt_output_parameters.output_rate_ms); + pvt_output_parameters.nmea_rate_ms = bc::lcm(configuration->property(role + ".nmea_rate_ms", pvt_output_parameters.nmea_rate_ms), pvt_output_parameters.output_rate_ms); + pvt_output_parameters.an_rate_ms = configuration->property(role + ".an_rate_ms", pvt_output_parameters.an_rate_ms); + + // Infer the type of receiver + /* + * TYPE | RECEIVER + * 0 | Unknown + * 1 | GPS L1 C/A + * 2 | GPS L2C + * 3 | GPS L5 + * 4 | Galileo E1B + * 5 | Galileo E5a + * 6 | Galileo E5b + * 7 | GPS L1 C/A + GPS L2C + * 8 | GPS L1 C/A + GPS L5 + * 9 | GPS L1 C/A + Galileo E1B + * 10 | GPS L1 C/A + Galileo E5a + * 11 | GPS L1 C/A + Galileo E5b + * 12 | Galileo E1B + GPS L2C + * 13 | Galileo E5a + GPS L5 + * 14 | Galileo E1B + Galileo E5a + * 15 | Galileo E1B + Galileo E5b + * 16 | GPS L2C + GPS L5 + * 17 | GPS L2C + Galileo E5a + * 18 | GPS L2C + Galileo E5b + * 19 | Galileo E5a + Galileo E5b + * 20 | GPS L5 + Galileo E5b + * 21 | GPS L1 C/A + Galileo E1B + GPS L2C + * 22 | GPS L1 C/A + Galileo E1B + GPS L5 + * 23 | GLONASS L1 C/A + * 24 | GLONASS L2 C/A + * 25 | GLONASS L1 C/A + GLONASS L2 C/A + * 26 | GPS L1 C/A + GLONASS L1 C/A + * 27 | Galileo E1B + GLONASS L1 C/A + * 28 | GPS L2C + GLONASS L1 C/A + * 29 | GPS L1 C/A + GLONASS L2 C/A + * 30 | Galileo E1B + GLONASS L2 C/A + * 31 | GPS L2C + GLONASS L2 C/A + * 32 | GPS L1 C/A + Galileo E1B + GPS L5 + Galileo E5a + * 33 | GPS L1 C/A + Galileo E1B + Galileo E5a + * + * Skipped previous values to avoid overlapping + * 100 | Galileo E6B + * 101 | Galileo E1B + Galileo E6B + * 102 | Galileo E5a + Galileo E6B + * 103 | Galileo E5b + Galileo E6B + * 104 | Galileo E1B + Galileo E5a + Galileo E6B + * 105 | Galileo E1B + Galileo E5b + Galileo E6B + * 106 | GPS L1 C/A + Galileo E1B + Galileo E6B + * 107 | GPS L1 C/A + Galileo E6B + * Skipped previous values to avoid overlapping + * 500 | BeiDou B1I + * 501 | BeiDou B1I + GPS L1 C/A + * 502 | BeiDou B1I + Galileo E1B + * 503 | BeiDou B1I + GLONASS L1 C/A + * 504 | BeiDou B1I + GPS L1 C/A + Galileo E1B + * 505 | BeiDou B1I + GPS L1 C/A + GLONASS L1 C/A + Galileo E1B + * 506 | BeiDou B1I + Beidou B3I + * Skipped previous values to avoid overlapping + * 600 | BeiDou B3I + * 601 | BeiDou B3I + GPS L2C + * 602 | BeiDou B3I + GLONASS L2 C/A + * 603 | BeiDou B3I + GPS L2C + GLONASS L2 C/A + * 604 | BeiDou B3I + GPS L1 C/A + * 605 | BeiDou B3I + Galileo E1B + * 606 | BeiDou B3I + GLONASS L1 C/A + * 607 | BeiDou B3I + GPS L1 C/A + Galileo E1B + * 608 | BeiDou B3I + GPS L1 C/A + Galileo E1B + BeiDou B1I + * 609 | BeiDou B3I + GPS L1 C/A + Galileo E1B + GLONASS L1 C/A + * 610 | BeiDou B3I + GPS L1 C/A + Galileo E1B + GLONASS L1 C/A + BeiDou B1I + * + * 1000 | GPS L1 C/A + GPS L2C + GPS L5 + * 1001 | GPS L1 C/A + Galileo E1B + GPS L2C + GPS L5 + Galileo E5a + */ + const int gps_1C_count = configuration->property("Channels_1C.count", 0); + const int gps_2S_count = configuration->property("Channels_2S.count", 0); + const int gps_L5_count = configuration->property("Channels_L5.count", 0); + const int gal_1B_count = configuration->property("Channels_1B.count", 0); + const int gal_E5a_count = configuration->property("Channels_5X.count", 0); + const int gal_E5b_count = configuration->property("Channels_7X.count", 0); + const int gal_E6_count = configuration->property("Channels_E6.count", 0); + const int glo_1G_count = configuration->property("Channels_1G.count", 0); + const int glo_2G_count = configuration->property("Channels_2G.count", 0); + const int bds_B1_count = configuration->property("Channels_B1.count", 0); + const int bds_B3_count = configuration->property("Channels_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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 1; // L1 + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 2; // GPS L2C + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 3; // L5 + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 4; // E1 + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 5; // E5a + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 6; + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 7; // GPS L1 C/A + GPS L2C + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 8; // L1+L5 + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 9; // L1+E1 + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 10; // GPS L1 C/A + Galileo E5a + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 11; + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 12; // Galileo E1B + GPS L2C + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 13; // L5+E5a + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 14; // Galileo E1B + Galileo E5a + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 15; + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 16; // GPS L2C + GPS L5 + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 17; // GPS L2C + Galileo E5a + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 18; // GPS L2C + Galileo E5b + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 19; // Galileo E5a + Galileo E5b + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 20; // GPS L5 + Galileo E5b + } + 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) && (gal_E6_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 + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 22; // GPS L1 C/A + Galileo E1B + GPS L5 + } + 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 23; // GLONASS L1 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 24; // GLONASS L2 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 25; // GLONASS L1 C/A + GLONASS L2 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 26; // GPS L1 C/A + GLONASS L1 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 27; // Galileo E1B + GLONASS L1 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 28; // GPS L2C + GLONASS L1 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 29; // GPS L1 C/A + GLONASS L2 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 30; // Galileo E1B + GLONASS L2 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 31; // GPS L2C + GLONASS L2 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 32; // L1+E1+L5+E5a + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 33; // L1+E1+E5a + } + // Galileo E6 + 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 100; // Galileo E6B + } + 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 101; // Galileo E1B + Galileo E6B + } + 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 102; // Galileo E5a + Galileo E6B + } + 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 103; // Galileo E5b + Galileo E6B + } + 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 104; // Galileo E1B + Galileo E5a + Galileo E6B + } + 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 105; // Galileo E1B + Galileo E5b + Galileo E6B + } + 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 106; // GPS L1 C/A + Galileo E1B + Galileo E6B + } + 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) && (gal_E6_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 107; // GPS L1 C/A + Galileo E6B + } + // BeiDou B1I Receiver + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 500; // Beidou B1I + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 501; // Beidou B1I + GPS L1 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 502; // Beidou B1I + Galileo E1B + } + 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 503; // Beidou B1I + GLONASS L1 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 504; // Beidou B1I + GPS L1 C/A + Galileo E1B + } + 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 505; // Beidou B1I + GPS L1 C/A + GLONASS L1 C/A + Galileo E1B + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count != 0) && (bds_B3_count != 0)) + { + pvt_output_parameters.type_of_receiver = 506; // Beidou B1I + Beidou B3I + } + // BeiDou B3I Receiver + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count != 0)) + { + pvt_output_parameters.type_of_receiver = 600; // Beidou B3I + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count != 0)) + { + pvt_output_parameters.type_of_receiver = 601; // Beidou B3I + GPS L2C + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count != 0)) + { + pvt_output_parameters.type_of_receiver = 602; // Beidou B3I + GLONASS L2 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count != 0) && (glo_2G_count != 0) && (bds_B1_count == 0) && (bds_B3_count != 0)) + { + pvt_output_parameters.type_of_receiver = 603; // Beidou B3I + GPS L2C + GLONASS L2 C/A + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 1000; // GPS L1 + GPS L2C + GPS L5 + } + 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) && (gal_E6_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + { + pvt_output_parameters.type_of_receiver = 1001; // GPS L1 + Galileo E1B + GPS L2C + GPS L5 + Galileo E5a + } + + // RTKLIB PVT solver options + // Settings 1 + int positioning_mode = -1; + const std::string default_pos_mode("Single"); + const std::string positioning_mode_str = configuration->property(role + ".positioning_mode", default_pos_mode); // (PMODE_XXX) see src/algorithms/libs/rtklib/rtklib.h + if (positioning_mode_str == "Single") + { + positioning_mode = PMODE_SINGLE; + } + if (positioning_mode_str == "Static") + { + positioning_mode = PMODE_STATIC; + } + if (positioning_mode_str == "Kinematic") + { + positioning_mode = PMODE_KINEMA; + } + if (positioning_mode_str == "PPP_Static") + { + positioning_mode = PMODE_PPP_STATIC; + } + if (positioning_mode_str == "PPP_Kinematic") + { + positioning_mode = PMODE_PPP_KINEMA; + } + + if (positioning_mode == -1) + { + // warn user and set the default + std::cout << "WARNING: Bad specification of positioning mode.\n" + << "positioning_mode possible values: Single / Static / Kinematic / PPP_Static / PPP_Kinematic\n" + << "positioning_mode specified value: " << positioning_mode_str << "\n" + << "Setting positioning_mode to Single\n" + << std::flush; + positioning_mode = PMODE_SINGLE; + } + + int num_bands = 0; + + if ((gps_1C_count > 0) || (gal_1B_count > 0) || (glo_1G_count > 0) || (bds_B1_count > 0)) + { + num_bands += 1; + } + if ((gps_2S_count > 0) || (glo_2G_count > 0) || (bds_B3_count > 0)) + { + num_bands += 1; + } + if (gal_E6_count > 0) + { + num_bands += 1; + } + if ((gal_E5a_count > 0) || (gps_L5_count > 0)) + { + num_bands += 1; + } + if (gal_E5b_count > 0) + { + num_bands += 1; + } + if (num_bands > 3) + { + LOG(WARNING) << "Too much bands: The PVT engine can only handle 3 bands, but " << num_bands << " were set"; + num_bands = 3; + } + + int number_of_frequencies = configuration->property(role + ".num_bands", num_bands); /* (1:L1, 2:L1+L2, 3:L1+L2+L5) */ + if ((number_of_frequencies < 1) || (number_of_frequencies > 3)) + { + // warn user and set the default + number_of_frequencies = num_bands; + } + + double elevation_mask = configuration->property(role + ".elevation_mask", 15.0); + if ((elevation_mask < 0.0) || (elevation_mask > 90.0)) + { + // warn user and set the default + LOG(WARNING) << "Erroneous Elevation Mask. Setting to default value of 15.0 degrees"; + elevation_mask = 15.0; + } + + int dynamics_model = configuration->property(role + ".dynamics_model", 0); /* dynamics model (0:none, 1:velocity, 2:accel) */ + if ((dynamics_model < 0) || (dynamics_model > 2)) + { + // warn user and set the default + LOG(WARNING) << "Erroneous Dynamics Model configuration. Setting to default value of (0:none)"; + dynamics_model = 0; + } + + const std::string default_iono_model("OFF"); + const std::string iono_model_str = configuration->property(role + ".iono_model", default_iono_model); /* (IONOOPT_XXX) see src/algorithms/libs/rtklib/rtklib.h */ + int iono_model = -1; + if (iono_model_str == "OFF") + { + iono_model = IONOOPT_OFF; + } + if (iono_model_str == "Broadcast") + { + iono_model = IONOOPT_BRDC; + } + if (iono_model_str == "SBAS") + { + iono_model = IONOOPT_SBAS; + } + if (iono_model_str == "Iono-Free-LC") + { + iono_model = IONOOPT_IFLC; + } + if (iono_model_str == "Estimate_STEC") + { + iono_model = IONOOPT_EST; + } + if (iono_model_str == "IONEX") + { + iono_model = IONOOPT_TEC; + } + if (iono_model == -1) + { + // warn user and set the default + std::cout << "WARNING: Bad specification of ionospheric model.\n" + << "iono_model possible values: OFF / Broadcast / SBAS / Iono-Free-LC / Estimate_STEC / IONEX\n" + << "iono_model specified value: " << iono_model_str << "\n" + << "Setting iono_model to OFF\n" + << std::flush; + iono_model = IONOOPT_OFF; /* 0: ionosphere option: correction off */ + } + + const std::string default_trop_model("OFF"); + int trop_model = -1; + const std::string trop_model_str = configuration->property(role + ".trop_model", default_trop_model); /* (TROPOPT_XXX) see src/algorithms/libs/rtklib/rtklib.h */ + if (trop_model_str == "OFF") + { + trop_model = TROPOPT_OFF; + } + if (trop_model_str == "Saastamoinen") + { + trop_model = TROPOPT_SAAS; + } + if (trop_model_str == "SBAS") + { + trop_model = TROPOPT_SBAS; + } + if (trop_model_str == "Estimate_ZTD") + { + trop_model = TROPOPT_EST; + } + if (trop_model_str == "Estimate_ZTD_Grad") + { + trop_model = TROPOPT_ESTG; + } + if (trop_model == -1) + { + // warn user and set the default + std::cout << "WARNING: Bad specification of tropospheric model.\n" + << "trop_model possible values: OFF / Saastamoinen / SBAS / Estimate_ZTD / Estimate_ZTD_Grad\n" + << "trop_model specified value: " << trop_model_str << "\n" + << "Setting trop_model to OFF\n" + << std::flush; + trop_model = TROPOPT_OFF; + } + + /* RTKLIB positioning options */ + int sat_PCV = 0; /* Set whether the satellite antenna PCV (phase center variation) model is used or not. This feature requires a Satellite Antenna PCV File. */ + int rec_PCV = 0; /* Set whether the receiver antenna PCV (phase center variation) model is used or not. This feature requires a Receiver Antenna PCV File. */ + + /* Set whether the phase windup correction for PPP modes is applied or not. Only applicable to PPP‐* modes.*/ + const int phwindup = configuration->property(role + ".phwindup", 0); + + /* Set whether the GPS Block IIA satellites in eclipse are excluded or not. + The eclipsing Block IIA satellites often degrade the PPP solutions due to unpredicted behavior of yaw‐attitude. Only applicable to PPP‐* modes.*/ + const int reject_GPS_IIA = configuration->property(role + ".reject_GPS_IIA", 0); + + /* Set whether RAIM (receiver autonomous integrity monitoring) FDE (fault detection and exclusion) feature is enabled or not. + In case of RAIM FDE enabled, a satellite is excluded if SSE (sum of squared errors) of residuals is over a threshold. + The excluded satellite is selected to indicate the minimum SSE. */ + const int raim_fde = configuration->property(role + ".raim_fde", 0); + + const int earth_tide = configuration->property(role + ".earth_tide", 0); + + int nsys = 0; + if ((gps_1C_count > 0) || (gps_2S_count > 0) || (gps_L5_count > 0)) + { + nsys += SYS_GPS; + } + if ((gal_1B_count > 0) || (gal_E5a_count > 0) || (gal_E5b_count > 0) || (gal_E6_count > 0)) + { + nsys += SYS_GAL; + } + if ((glo_1G_count > 0) || (glo_2G_count > 0)) + { + nsys += SYS_GLO; + } + if ((bds_B1_count > 0) || (bds_B3_count > 0)) + { + nsys += SYS_BDS; + } + + int navigation_system = configuration->property(role + ".navigation_system", nsys); /* (SYS_XXX) see src/algorithms/libs/rtklib/rtklib.h */ + if ((navigation_system < 1) || (navigation_system > 255)) /* GPS: 1 SBAS: 2 GPS+SBAS: 3 Galileo: 8 Galileo+GPS: 9 GPS+SBAS+Galileo: 11 All: 255 */ + { + // warn user and set the default + LOG(WARNING) << "Erroneous Navigation System. Setting to default value of (0:none)"; + navigation_system = nsys; + } + + // Settings 2 + const std::string default_gps_ar("Continuous"); + const std::string integer_ambiguity_resolution_gps_str = configuration->property(role + ".AR_GPS", default_gps_ar); /* Integer Ambiguity Resolution mode for GPS (0:off,1:continuous,2:instantaneous,3:fix and hold,4:ppp-ar) */ + int integer_ambiguity_resolution_gps = -1; + if (integer_ambiguity_resolution_gps_str == "OFF") + { + integer_ambiguity_resolution_gps = ARMODE_OFF; + } + if (integer_ambiguity_resolution_gps_str == "Continuous") + { + integer_ambiguity_resolution_gps = ARMODE_CONT; + } + if (integer_ambiguity_resolution_gps_str == "Instantaneous") + { + integer_ambiguity_resolution_gps = ARMODE_INST; + } + if (integer_ambiguity_resolution_gps_str == "Fix-and-Hold") + { + integer_ambiguity_resolution_gps = ARMODE_FIXHOLD; + } + if (integer_ambiguity_resolution_gps_str == "PPP-AR") + { + integer_ambiguity_resolution_gps = ARMODE_PPPAR; + } + if (integer_ambiguity_resolution_gps == -1) + { + // warn user and set the default + std::cout << "WARNING: Bad specification of GPS ambiguity resolution method.\n" + << "AR_GPS possible values: OFF / Continuous / Instantaneous / Fix-and-Hold / PPP-AR\n" + << "AR_GPS specified value: " << integer_ambiguity_resolution_gps_str << "\n" + << "Setting AR_GPS to OFF\n" + << std::flush; + integer_ambiguity_resolution_gps = ARMODE_OFF; + } + + int integer_ambiguity_resolution_glo = configuration->property(role + ".AR_GLO", 1); /* Integer Ambiguity Resolution mode for GLONASS (0:off,1:on,2:auto cal,3:ext cal) */ + if ((integer_ambiguity_resolution_glo < 0) || (integer_ambiguity_resolution_glo > 3)) + { + // warn user and set the default + LOG(WARNING) << "Erroneous Integer Ambiguity Resolution for GLONASS . Setting to default value of (1:on)"; + integer_ambiguity_resolution_glo = 1; + } + + int integer_ambiguity_resolution_bds = configuration->property(role + ".AR_DBS", 1); /* Integer Ambiguity Resolution mode for BEIDOU (0:off,1:on) */ + if ((integer_ambiguity_resolution_bds < 0) || (integer_ambiguity_resolution_bds > 1)) + { + // warn user and set the default + LOG(WARNING) << "Erroneous Integer Ambiguity Resolution for BEIDOU . Setting to default value of (1:on)"; + integer_ambiguity_resolution_bds = 1; + } + + const double min_ratio_to_fix_ambiguity = configuration->property(role + ".min_ratio_to_fix_ambiguity", 3.0); /* Set the integer ambiguity validation threshold for ratio‐test, + which uses the ratio of squared residuals of the best integer vector to the second‐best vector. */ + + const int min_lock_to_fix_ambiguity = configuration->property(role + ".min_lock_to_fix_ambiguity", 0); /* Set the minimum lock count to fix integer ambiguity.FLAGS_RINEX_version. + If the lock count is less than the value, the ambiguity is excluded from the fixed integer vector. */ + + const double min_elevation_to_fix_ambiguity = configuration->property(role + ".min_elevation_to_fix_ambiguity", 0.0); /* Set the minimum elevation (deg) to fix integer ambiguity. + If the elevation of the satellite is less than the value, the ambiguity is excluded from the fixed integer vector. */ + + const int outage_reset_ambiguity = configuration->property(role + ".outage_reset_ambiguity", 5); /* Set the outage count to reset ambiguity. If the data outage count is over the value, the estimated ambiguity is reset to the initial value. */ + + const double slip_threshold = configuration->property(role + ".slip_threshold", 0.05); /* set the cycle‐slip threshold (m) of geometry‐free LC carrier‐phase difference between epochs */ + + const double threshold_reject_gdop = configuration->property(role + ".threshold_reject_gdop", 30.0); /* reject threshold of GDOP. If the GDOP is over the value, the observable is excluded for the estimation process as an outlier. */ + + const double threshold_reject_innovation = configuration->property(role + ".threshold_reject_innovation", 30.0); /* reject threshold of innovation (m). If the innovation is over the value, the observable is excluded for the estimation process as an outlier. */ + + const int number_filter_iter = configuration->property(role + ".number_filter_iter", 1); /* Set the number of iteration in the measurement update of the estimation filter. + If the baseline length is very short like 1 m, the iteration may be effective to handle + the nonlinearity of measurement equation. */ + + // Statistics + const double bias_0 = configuration->property(role + ".bias_0", 30.0); + + const double iono_0 = configuration->property(role + ".iono_0", 0.03); + + const double trop_0 = configuration->property(role + ".trop_0", 0.3); + + const double sigma_bias = configuration->property(role + ".sigma_bias", 1e-4); /* Set the process noise standard deviation of carrier‐phase + bias (ambiguity) (cycle/sqrt(s)) */ + + const double sigma_iono = configuration->property(role + ".sigma_iono", 1e-3); /* Set the process noise standard deviation of vertical ionospheric delay per 10 km baseline (m/sqrt(s)). */ + + const double sigma_trop = configuration->property(role + ".sigma_trop", 1e-4); /* Set the process noise standard deviation of zenith tropospheric delay (m/sqrt(s)). */ + + const double sigma_acch = configuration->property(role + ".sigma_acch", 1e-1); /* Set the process noise standard deviation of the receiver acceleration as + the horizontal component. (m/s2/sqrt(s)). If Receiver Dynamics is set to OFF, they are not used. */ + + const double sigma_accv = configuration->property(role + ".sigma_accv", 1e-2); /* Set the process noise standard deviation of the receiver acceleration as + the vertical component. (m/s2/sqrt(s)). If Receiver Dynamics is set to OFF, they are not used. */ + + const double sigma_pos = configuration->property(role + ".sigma_pos", 0.0); + + const double code_phase_error_ratio_l1 = configuration->property(role + ".code_phase_error_ratio_l1", 100.0); + const double code_phase_error_ratio_l2 = configuration->property(role + ".code_phase_error_ratio_l2", 100.0); + const double code_phase_error_ratio_l5 = configuration->property(role + ".code_phase_error_ratio_l5", 100.0); + const double carrier_phase_error_factor_a = configuration->property(role + ".carrier_phase_error_factor_a", 0.003); + const double carrier_phase_error_factor_b = configuration->property(role + ".carrier_phase_error_factor_b", 0.003); + + const bool bancroft_init = configuration->property(role + ".bancroft_init", true); + + snrmask_t snrmask = {{}, {{}, {}}}; + + prcopt_t rtklib_configuration_options = { + positioning_mode, /* positioning mode (PMODE_XXX) see src/algorithms/libs/rtklib/rtklib.h */ + 0, /* solution type (0:forward,1:backward,2:combined) */ + number_of_frequencies, /* number of frequencies (1:L1, 2:L1+L2, 3:L1+L2+L5)*/ + navigation_system, /* navigation system */ + elevation_mask * D2R, /* elevation mask angle (degrees) */ + snrmask, /* snrmask_t snrmask SNR mask */ + 0, /* satellite ephemeris/clock (EPHOPT_XXX) */ + integer_ambiguity_resolution_gps, /* AR mode (0:off,1:continuous,2:instantaneous,3:fix and hold,4:ppp-ar) */ + integer_ambiguity_resolution_glo, /* GLONASS AR mode (0:off,1:on,2:auto cal,3:ext cal) */ + integer_ambiguity_resolution_bds, /* BeiDou AR mode (0:off,1:on) */ + outage_reset_ambiguity, /* obs outage count to reset bias */ + min_lock_to_fix_ambiguity, /* min lock count to fix ambiguity */ + 10, /* min fix count to hold ambiguity */ + 1, /* max iteration to resolve ambiguity */ + iono_model, /* ionosphere option (IONOOPT_XXX) */ + trop_model, /* troposphere option (TROPOPT_XXX) */ + dynamics_model, /* dynamics model (0:none, 1:velocity, 2:accel) */ + earth_tide, /* earth tide correction (0:off,1:solid,2:solid+otl+pole) */ + number_filter_iter, /* number of filter iteration */ + 0, /* code smoothing window size (0:none) */ + 0, /* interpolate reference obs (for post mission) */ + 0, /* sbssat_t sbssat SBAS correction options */ + 0, /* sbsion_t sbsion[MAXBAND+1] SBAS satellite selection (0:all) */ + 0, /* rover position for fixed mode */ + 0, /* base position for relative mode */ + /* 0:pos in prcopt, 1:average of single pos, */ + /* 2:read from file, 3:rinex header, 4:rtcm pos */ + {code_phase_error_ratio_l1, code_phase_error_ratio_l2, code_phase_error_ratio_l5}, /* eratio[NFREQ] code/phase error ratio */ + {100.0, carrier_phase_error_factor_a, carrier_phase_error_factor_b, 0.0, 1.0}, /* err[5]: measurement error factor [0]:reserved, [1-3]:error factor a/b/c of phase (m) , [4]:doppler frequency (hz) */ + {bias_0, iono_0, trop_0}, /* std[3]: initial-state std [0]bias,[1]iono [2]trop*/ + {sigma_bias, sigma_iono, sigma_trop, sigma_acch, sigma_accv, sigma_pos}, /* prn[6] process-noise std */ + 5e-12, /* sclkstab: satellite clock stability (sec/sec) */ + {min_ratio_to_fix_ambiguity, 0.9999, 0.25, 0.1, 0.05, 0.0, 0.0, 0.0}, /* thresar[8]: AR validation threshold */ + min_elevation_to_fix_ambiguity, /* elevation mask of AR for rising satellite (deg) */ + 0.0, /* elevation mask to hold ambiguity (deg) */ + slip_threshold, /* slip threshold of geometry-free phase (m) */ + 30.0, /* max difference of time (sec) */ + threshold_reject_innovation, /* reject threshold of innovation (m) */ + threshold_reject_gdop, /* reject threshold of gdop */ + {}, /* double baseline[2] baseline length constraint {const,sigma} (m) */ + {}, /* double ru[3] rover position for fixed mode {x,y,z} (ecef) (m) */ + {}, /* double rb[3] base position for relative mode {x,y,z} (ecef) (m) */ + {"", ""}, /* char anttype[2][MAXANT] antenna types {rover,base} */ + {{}, {}}, /* double antdel[2][3] antenna delta {{rov_e,rov_n,rov_u},{ref_e,ref_n,ref_u}} */ + {}, /* pcv_t pcvr[2] receiver antenna parameters {rov,base} */ + {}, /* unsigned char exsats[MAXSAT] excluded satellites (1:excluded, 2:included) */ + 0, /* max averaging epoches */ + 0, /* initialize by restart */ + 1, /* output single by dgps/float/fix/ppp outage */ + {"", ""}, /* char rnxopt[2][256] rinex options {rover,base} */ + {sat_PCV, rec_PCV, phwindup, reject_GPS_IIA, raim_fde}, /* posopt[6] positioning options [0]: satellite and receiver antenna PCV model; [1]: interpolate antenna parameters; [2]: apply phase wind-up correction for PPP modes; [3]: exclude measurements of GPS Block IIA satellites satellite [4]: RAIM FDE (fault detection and exclusion) [5]: handle day-boundary clock jump */ + 0, /* solution sync mode (0:off,1:on) */ + {{}, {}}, /* odisp[2][6*11] ocean tide loading parameters {rov,base} */ + {{}, {{}, {}}, {{}, {}}, {}, {}}, /* exterr_t exterr extended receiver error model */ + 0, /* disable L2-AR */ + {}, /* char pppopt[256] ppp option "-GAP_RESION=" default gap to reset iono parameters (ep) */ + bancroft_init /* enable Bancroft initialization for the first iteration of the PVT computation, useful in some geometries */ + }; + + rtkinit(&rtk, &rtklib_configuration_options); + + // Outputs + const bool default_output_enabled = configuration->property(role + ".output_enabled", true); + pvt_output_parameters.output_enabled = default_output_enabled; + pvt_output_parameters.rinex_output_enabled = configuration->property(role + ".rinex_output_enabled", default_output_enabled); + pvt_output_parameters.gpx_output_enabled = configuration->property(role + ".gpx_output_enabled", default_output_enabled); + pvt_output_parameters.geojson_output_enabled = configuration->property(role + ".geojson_output_enabled", default_output_enabled); + pvt_output_parameters.kml_output_enabled = configuration->property(role + ".kml_output_enabled", default_output_enabled); + pvt_output_parameters.xml_output_enabled = configuration->property(role + ".xml_output_enabled", default_output_enabled); + pvt_output_parameters.nmea_output_file_enabled = configuration->property(role + ".nmea_output_file_enabled", default_output_enabled); + pvt_output_parameters.rtcm_output_file_enabled = configuration->property(role + ".rtcm_output_file_enabled", false); + + const std::string default_output_path = configuration->property(role + ".output_path", std::string(".")); + pvt_output_parameters.output_path = default_output_path; + pvt_output_parameters.rinex_output_path = configuration->property(role + ".rinex_output_path", default_output_path); + pvt_output_parameters.gpx_output_path = configuration->property(role + ".gpx_output_path", default_output_path); + pvt_output_parameters.geojson_output_path = configuration->property(role + ".geojson_output_path", default_output_path); + pvt_output_parameters.kml_output_path = configuration->property(role + ".kml_output_path", default_output_path); + pvt_output_parameters.xml_output_path = configuration->property(role + ".xml_output_path", default_output_path); + pvt_output_parameters.nmea_output_file_path = configuration->property(role + ".nmea_output_file_path", default_output_path); + pvt_output_parameters.rtcm_output_file_path = configuration->property(role + ".rtcm_output_file_path", default_output_path); + + // Read PVT MONITOR Configuration + pvt_output_parameters.monitor_enabled = configuration->property(role + ".enable_monitor", false); + pvt_output_parameters.udp_addresses = configuration->property(role + ".monitor_client_addresses", std::string("127.0.0.1")); + pvt_output_parameters.udp_port = configuration->property(role + ".monitor_udp_port", 1234); + pvt_output_parameters.protobuf_enabled = configuration->property(role + ".enable_protobuf", true); + if (configuration->property("Monitor.enable_protobuf", false) == true) + { + pvt_output_parameters.protobuf_enabled = true; + } + + // Read EPHEMERIS MONITOR Configuration + pvt_output_parameters.monitor_ephemeris_enabled = configuration->property(role + ".enable_monitor_ephemeris", false); + pvt_output_parameters.udp_eph_addresses = configuration->property(role + ".monitor_ephemeris_client_addresses", std::string("127.0.0.1")); + pvt_output_parameters.udp_eph_port = configuration->property(role + ".monitor_ephemeris_udp_port", 1234); + + // Show time in local zone + pvt_output_parameters.show_local_time_zone = configuration->property(role + ".show_local_time_zone", false); + + // Enable or disable rx clock correction in observables + pvt_output_parameters.enable_rx_clock_correction = configuration->property(role + ".enable_rx_clock_correction", false); + + // Set maximum clock offset allowed if pvt_output_parameters.enable_rx_clock_correction = false + pvt_output_parameters.max_obs_block_rx_clock_offset_ms = configuration->property(role + ".max_clock_offset_ms", pvt_output_parameters.max_obs_block_rx_clock_offset_ms); + + // Source timetag + pvt_output_parameters.log_source_timetag = configuration->property(role + ".log_timetag", pvt_output_parameters.log_source_timetag); + pvt_output_parameters.log_source_timetag_file = configuration->property(role + ".log_source_timetag_file", pvt_output_parameters.log_source_timetag_file); + + // Use E6 for PVT + pvt_output_parameters.use_e6_for_pvt = configuration->property(role + ".use_e6_for_pvt", pvt_output_parameters.use_e6_for_pvt); + pvt_output_parameters.use_has_corrections = configuration->property(role + ".use_has_corrections", pvt_output_parameters.use_has_corrections); + + // Use unhealthy satellites + pvt_output_parameters.use_unhealthy_sats = configuration->property(role + ".use_unhealthy_sats", pvt_output_parameters.use_unhealthy_sats); + + // make PVT object + pvt_ = rtklib_make_pvt_gs(in_streams_, pvt_output_parameters, rtk); + DLOG(INFO) << "pvt(" << pvt_->unique_id() << ")"; + if (out_streams_ > 0) + { + LOG(ERROR) << "The PVT block does not have an output stream"; + } +} + + +Rtklib_Pvt::~Rtklib_Pvt() +{ + DLOG(INFO) << "PVT adapter destructor called."; + rtkfree(&rtk); +} + + +bool Rtklib_Pvt::get_latest_PVT(double* longitude_deg, + double* latitude_deg, + double* height_m, + double* ground_speed_kmh, + double* course_over_ground_deg, + time_t* UTC_time) +{ + return pvt_->get_latest_PVT(longitude_deg, + latitude_deg, + height_m, + ground_speed_kmh, + course_over_ground_deg, + UTC_time); +} + + +void Rtklib_Pvt::clear_ephemeris() +{ + pvt_->clear_ephemeris(); +} + + +std::map Rtklib_Pvt::get_gps_ephemeris() const +{ + return pvt_->get_gps_ephemeris_map(); +} + + +std::map Rtklib_Pvt::get_galileo_ephemeris() const +{ + return pvt_->get_galileo_ephemeris_map(); +} + + +std::map Rtklib_Pvt::get_gps_almanac() const +{ + return pvt_->get_gps_almanac_map(); +} + + +std::map Rtklib_Pvt::get_galileo_almanac() const +{ + return pvt_->get_galileo_almanac_map(); +} + + +void Rtklib_Pvt::connect(gr::top_block_sptr top_block) +{ + if (top_block) + { /* top_block is not null */ + }; + // Nothing to connect internally + DLOG(INFO) << "nothing to connect internally"; +} + + +void Rtklib_Pvt::disconnect(gr::top_block_sptr top_block) +{ + if (top_block) + { /* top_block is not null */ + }; + // Nothing to disconnect +} + + +gr::basic_block_sptr Rtklib_Pvt::get_left_block() +{ + return pvt_; +} + + +gr::basic_block_sptr Rtklib_Pvt::get_right_block() +{ + return nullptr; // this is a sink, nothing downstream +} diff --git a/src/algorithms/PVT/libs/pvt_conf.h b/src/algorithms/PVT/libs/pvt_conf.h old mode 100644 new mode 100755 index bf4a3501a..f194c0596 --- a/src/algorithms/PVT/libs/pvt_conf.h +++ b/src/algorithms/PVT/libs/pvt_conf.h @@ -1,109 +1,110 @@ -/*! - * \file pvt_conf.h - * \brief Class that contains all the configuration parameters for the PVT block - * \author Carles Fernandez, 2018. cfernandez(at)cttc.es - * - * ----------------------------------------------------------------------------- - * - * GNSS-SDR is a Global Navigation Satellite System software-defined receiver. - * This file is part of GNSS-SDR. - * - * Copyright (C) 2010-2020 (see AUTHORS file for a list of contributors) - * SPDX-License-Identifier: GPL-3.0-or-later - * - * ----------------------------------------------------------------------------- - */ - -#ifndef GNSS_SDR_PVT_CONF_H -#define GNSS_SDR_PVT_CONF_H - -#include -#include -#include - -/** \addtogroup PVT - * \{ */ -/** \addtogroup PVT_libs - * \{ */ - - -class Pvt_Conf -{ -public: - std::map rtcm_msg_rate_ms; - - std::string rinex_name = std::string("-"); - std::string dump_filename; - std::string nmea_dump_filename; - std::string nmea_dump_devname; - std::string rtcm_dump_devname; - std::string an_dump_devname; - std::string output_path = std::string("."); - std::string rinex_output_path = std::string("."); - std::string gpx_output_path = std::string("."); - std::string geojson_output_path = std::string("."); - std::string nmea_output_file_path = std::string("."); - std::string kml_output_path = std::string("."); - std::string xml_output_path = std::string("."); - std::string rtcm_output_file_path = std::string("."); - std::string udp_addresses; - std::string udp_eph_addresses; - std::string log_source_timetag_file; - - uint32_t type_of_receiver = 0; - uint32_t observable_interval_ms = 20; - - int32_t output_rate_ms = 0; - int32_t display_rate_ms = 0; - int32_t kml_rate_ms = 1000; - int32_t gpx_rate_ms = 1000; - int32_t geojson_rate_ms = 1000; - int32_t nmea_rate_ms = 1000; - int32_t rinex_version = 0; - int32_t rinexobs_rate_ms = 0; - int32_t an_rate_ms = 1000; - int32_t max_obs_block_rx_clock_offset_ms = 40; - int udp_port = 0; - int udp_eph_port = 0; - int rtk_trace_level = 0; - - uint16_t rtcm_tcp_port = 0; - uint16_t rtcm_station_id = 0; - - bool flag_nmea_tty_port = false; - bool flag_rtcm_server = false; - bool flag_rtcm_tty_port = false; - bool output_enabled = true; - bool rinex_output_enabled = true; - bool gpx_output_enabled = true; - bool geojson_output_enabled = true; - bool nmea_output_file_enabled = true; - bool an_output_enabled = false; - bool kml_output_enabled = true; - bool xml_output_enabled = true; - bool rtcm_output_file_enabled = true; - bool monitor_enabled = false; - bool monitor_ephemeris_enabled = false; - bool protobuf_enabled = true; - bool enable_rx_clock_correction = true; - bool show_local_time_zone = false; - bool pre_2009_file = false; - bool dump = false; - bool dump_mat = true; - bool log_source_timetag; - bool use_e6_for_pvt = true; - bool use_has_corrections = true; - bool use_unhealthy_sats = false; - - // PVT KF parameters - bool enable_pvt_kf = false; - double measures_ecef_pos_sd_m = 1.0; - double measures_ecef_vel_sd_ms = 0.1; - double system_ecef_pos_sd_m = 0.01; - double system_ecef_vel_sd_ms = 0.001; -}; - - -/** \} */ -/** \} */ -#endif // GNSS_SDR_PVT_CONF_H +/*! + * \file pvt_conf.h + * \brief Class that contains all the configuration parameters for the PVT block + * \author Carles Fernandez, 2018. cfernandez(at)cttc.es + * + * ----------------------------------------------------------------------------- + * + * GNSS-SDR is a Global Navigation Satellite System software-defined receiver. + * This file is part of GNSS-SDR. + * + * Copyright (C) 2010-2020 (see AUTHORS file for a list of contributors) + * SPDX-License-Identifier: GPL-3.0-or-later + * + * ----------------------------------------------------------------------------- + */ + +#ifndef GNSS_SDR_PVT_CONF_H +#define GNSS_SDR_PVT_CONF_H + +#include +#include +#include + +/** \addtogroup PVT + * \{ */ +/** \addtogroup PVT_libs + * \{ */ + + +class Pvt_Conf +{ +public: + std::map rtcm_msg_rate_ms; + + std::string rinex_name = std::string("-"); + std::string dump_filename; + std::string nmea_dump_filename; + std::string nmea_dump_devname; + std::string rtcm_dump_devname; + std::string an_dump_devname; + std::string output_path = std::string("."); + std::string rinex_output_path = std::string("."); + std::string gpx_output_path = std::string("."); + std::string geojson_output_path = std::string("."); + std::string nmea_output_file_path = std::string("."); + std::string kml_output_path = std::string("."); + std::string xml_output_path = std::string("."); + std::string rtcm_output_file_path = std::string("."); + std::string udp_addresses; + std::string udp_eph_addresses; + std::string log_source_timetag_file; + + uint32_t type_of_receiver = 0; + uint32_t observable_interval_ms = 20; + + int32_t output_rate_ms = 0; + int32_t display_rate_ms = 0; + int32_t kml_rate_ms = 1000; + int32_t gpx_rate_ms = 1000; + int32_t geojson_rate_ms = 1000; + int32_t nmea_rate_ms = 1000; + int32_t rinex_version = 0; + int32_t rinexobs_rate_ms = 0; + int32_t an_rate_ms = 1000; + int32_t max_obs_block_rx_clock_offset_ms = 40; + int udp_port = 0; + int udp_eph_port = 0; + int rtk_trace_level = 0; + + uint16_t rtcm_tcp_port = 0; + uint16_t rtcm_station_id = 0; + + bool flag_nmea_tty_port = false; + bool flag_rtcm_server = false; + bool flag_rtcm_tty_port = false; + bool output_enabled = true; + bool rinex_output_enabled = true; + bool gpx_output_enabled = true; + bool geojson_output_enabled = true; + bool nmea_output_file_enabled = true; + bool an_output_enabled = false; + bool kml_output_enabled = true; + bool xml_output_enabled = true; + bool rtcm_output_file_enabled = true; + bool monitor_enabled = false; + bool monitor_ephemeris_enabled = false; + bool protobuf_enabled = true; + bool enable_rx_clock_correction = true; + bool show_local_time_zone = false; + bool pre_2009_file = false; + bool dump = false; + bool dump_mat = true; + bool log_source_timetag; + bool use_e6_for_pvt = true; + bool use_has_corrections = true; + bool use_unhealthy_sats = false; + + // PVT KF parameters + bool enable_pvt_kf = false; + bool estatic_measures_sd = false; + double measures_ecef_pos_sd_m = 1.0; + double measures_ecef_vel_sd_ms = 0.1; + double system_ecef_pos_sd_m = 0.01; + double system_ecef_vel_sd_ms = 0.001; +}; + + +/** \} */ +/** \} */ +#endif // GNSS_SDR_PVT_CONF_H diff --git a/src/algorithms/PVT/libs/pvt_kf.cc b/src/algorithms/PVT/libs/pvt_kf.cc old mode 100644 new mode 100755 index 9a47732a0..17336e0fa --- a/src/algorithms/PVT/libs/pvt_kf.cc +++ b/src/algorithms/PVT/libs/pvt_kf.cc @@ -1,147 +1,162 @@ -/*! - * \file pvt_kf.cc - * \brief Kalman Filter for Position and Velocity - * \author Javier Arribas, 2023. jarribas(at)cttc.es - * - * - * ----------------------------------------------------------------------------- - * - * GNSS-SDR is a Global Navigation Satellite System software-defined receiver. - * This file is part of GNSS-SDR. - * - * Copyright (C) 2010-2023 (see AUTHORS file for a list of contributors) - * SPDX-License-Identifier: GPL-3.0-or-later - * - * ----------------------------------------------------------------------------- - */ - -#include "pvt_kf.h" -#include - - -void Pvt_Kf::init_Kf(const arma::vec& p, - const arma::vec& v, - const arma::vec& res_p, - double solver_interval_s, - double measures_ecef_pos_sd_m, - double measures_ecef_vel_sd_ms, - double system_ecef_pos_sd_m, - double system_ecef_vel_sd_ms) -{ - // Kalman Filter class variables - const double Ti = solver_interval_s; - - d_F = {{1.0, 0.0, 0.0, Ti, 0.0, 0.0}, - {0.0, 1.0, 0.0, 0.0, Ti, 0.0}, - {0.0, 0.0, 1.0, 0.0, 0.0, Ti}, - {0.0, 0.0, 0.0, 1.0, 0.0, 0.0}, - {0.0, 0.0, 0.0, 0.0, 1.0, 0.0}, - {0.0, 0.0, 0.0, 0.0, 0.0, 1.0}}; - - d_H = arma::eye(6, 6); - - // measurement matrix static covariances - d_R = {{res_p[0], res_p[3], res_p[5], 0.0, 0.0, 0.0}, - {res_p[3], res_p[1], res_p[4], 0.0, 0.0, 0.0}, - {res_p[4], res_p[5], res_p[2], 0.0, 0.0, 0.0}, - {0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, - {0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0}, - {0.0, 0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0)}}; - - // system covariance matrix (static) - d_Q = {{pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0, 0.0}, - {0.0, pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0}, - {0.0, 0.0, pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0}, - {0.0, 0.0, 0.0, pow(system_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, - {0.0, 0.0, 0.0, 0.0, pow(system_ecef_vel_sd_ms, 2.0), 0.0}, - {0.0, 0.0, 0.0, 0.0, 0.0, pow(system_ecef_vel_sd_ms, 2.0)}}; - - // initial Kalman covariance matrix - d_P_old_old = {{pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0, 0.0}, - {0.0, pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0}, - {0.0, 0.0, pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0}, - {0.0, 0.0, 0.0, pow(system_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, - {0.0, 0.0, 0.0, 0.0, pow(system_ecef_vel_sd_ms, 2.0), 0.0}, - {0.0, 0.0, 0.0, 0.0, 0.0, pow(system_ecef_vel_sd_ms, 2.0)}}; - - // states: position ecef [m], velocity ecef [m/s] - d_x_old_old = arma::zeros(6); - d_x_old_old.subvec(0, 2) = p; - d_x_old_old.subvec(3, 5) = v; - - d_initialized = true; - - DLOG(INFO) << "Ti: " << Ti; - DLOG(INFO) << "F: " << d_F; - DLOG(INFO) << "H: " << d_H; - DLOG(INFO) << "R: " << d_R; - DLOG(INFO) << "Q: " << d_Q; - DLOG(INFO) << "P: " << d_P_old_old; - DLOG(INFO) << "x: " << d_x_old_old; -} - - -bool Pvt_Kf::is_initialized() const -{ - return d_initialized; -} - - -void Pvt_Kf::reset_Kf() -{ - d_initialized = false; -} - - -void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p) -{ - if (d_initialized) - { - // Kalman loop - // Prediction - d_x_new_old = d_F * d_x_old_old; - d_P_new_old = d_F * d_P_old_old * d_F.t() + d_Q; - - // Measurement update - try - { - // Measurement residuals - d_R(0, 0) = res_p[0]; - d_R(0, 1) = res_p[3]; - d_R(0, 2) = res_p[5]; - d_R(1, 0) = res_p[3]; - d_R(1, 1) = res_p[1]; - d_R(1, 2) = res_p[4]; - d_R(2, 0) = res_p[5]; - d_R(2, 1) = res_p[4]; - d_R(2, 2) = res_p[2]; - - // Measurement update - arma::vec z = arma::join_cols(p, v); - arma::mat K = d_P_new_old * d_H.t() * arma::inv(d_H * d_P_new_old * d_H.t() + d_R); // Kalman gain - - d_x_new_new = d_x_new_old + K * (z - d_H * d_x_new_old); - arma::mat A = (arma::eye(6, 6) - K * d_H); - d_P_new_new = A * d_P_new_old * A.t() + K * d_R * K.t(); - - // prepare data for next KF epoch - d_x_old_old = d_x_new_new; - d_P_old_old = d_P_new_new; - } - catch (...) - { - d_x_new_new = d_x_new_old; - this->reset_Kf(); - } - } -} - - -void Pvt_Kf::get_pv_Kf(arma::vec& p, arma::vec& v) const -{ - if (d_initialized) - { - p = d_x_new_new.subvec(0, 2); - v = d_x_new_new.subvec(3, 5); - } -} +/*! + * \file pvt_kf.cc + * \brief Kalman Filter for Position and Velocity + * \author Javier Arribas, 2023. jarribas(at)cttc.es + * + * + * ----------------------------------------------------------------------------- + * + * GNSS-SDR is a Global Navigation Satellite System software-defined receiver. + * This file is part of GNSS-SDR. + * + * Copyright (C) 2010-2023 (see AUTHORS file for a list of contributors) + * SPDX-License-Identifier: GPL-3.0-or-later + * + * ----------------------------------------------------------------------------- + */ + +#include "pvt_kf.h" +#include + + +void Pvt_Kf::init_Kf(const arma::vec& p, + const arma::vec& v, + const arma::vec& res_p, + double solver_interval_s, + bool estatic_measures_sd, + double measures_ecef_pos_sd_m, + double measures_ecef_vel_sd_ms, + double system_ecef_pos_sd_m, + double system_ecef_vel_sd_ms) +{ + // Kalman Filter class variables + const double Ti = solver_interval_s; + + d_F = {{1.0, 0.0, 0.0, Ti, 0.0, 0.0}, + {0.0, 1.0, 0.0, 0.0, Ti, 0.0}, + {0.0, 0.0, 1.0, 0.0, 0.0, Ti}, + {0.0, 0.0, 0.0, 1.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, 1.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, 1.0}}; + + d_H = arma::eye(6, 6); + + // measurement matrix static covariances + if(estatic_measures_sd){ + d_R = {{pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0)}}; + + d_static = true; + + }else{ + d_R = {{res_p[0], res_p[3], res_p[5], 0.0, 0.0, 0.0}, + {res_p[3], res_p[1], res_p[4], 0.0, 0.0, 0.0}, + {res_p[4], res_p[5], res_p[2], 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0)}}; + + d_static = false; + } + // system covariance matrix (static) + d_Q = {{pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, pow(system_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, pow(system_ecef_vel_sd_ms, 2.0), 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, pow(system_ecef_vel_sd_ms, 2.0)}}; + + // initial Kalman covariance matrix + d_P_old_old = {{pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, pow(system_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, pow(system_ecef_vel_sd_ms, 2.0), 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, pow(system_ecef_vel_sd_ms, 2.0)}}; + + // states: position ecef [m], velocity ecef [m/s] + d_x_old_old = arma::zeros(6); + d_x_old_old.subvec(0, 2) = p; + d_x_old_old.subvec(3, 5) = v; + + d_initialized = true; + + DLOG(INFO) << "Ti: " << Ti; + DLOG(INFO) << "F: " << d_F; + DLOG(INFO) << "H: " << d_H; + DLOG(INFO) << "R: " << d_R; + DLOG(INFO) << "Q: " << d_Q; + DLOG(INFO) << "P: " << d_P_old_old; + DLOG(INFO) << "x: " << d_x_old_old; +} + + +bool Pvt_Kf::is_initialized() const +{ + return d_initialized; +} + + +void Pvt_Kf::reset_Kf() +{ + d_initialized = false; +} + + +void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p) +{ + if (d_initialized) + { + // Kalman loop + // Prediction + d_x_new_old = d_F * d_x_old_old; + d_P_new_old = d_F * d_P_old_old * d_F.t() + d_Q; + + // Measurement update + try + { + if(!d_static){ + // Measurement residuals update + d_R(0, 0) = res_p[0]; + d_R(0, 1) = res_p[3]; + d_R(0, 2) = res_p[5]; + d_R(1, 0) = res_p[3]; + d_R(1, 1) = res_p[1]; + d_R(1, 2) = res_p[4]; + d_R(2, 0) = res_p[5]; + d_R(2, 1) = res_p[4]; + d_R(2, 2) = res_p[2]; + } + // Measurement update + arma::vec z = arma::join_cols(p, v); + arma::mat K = d_P_new_old * d_H.t() * arma::inv(d_H * d_P_new_old * d_H.t() + d_R); // Kalman gain + + d_x_new_new = d_x_new_old + K * (z - d_H * d_x_new_old); + arma::mat A = (arma::eye(6, 6) - K * d_H); + d_P_new_new = A * d_P_new_old * A.t() + K * d_R * K.t(); + + // prepare data for next KF epoch + d_x_old_old = d_x_new_new; + d_P_old_old = d_P_new_new; + } + catch (...) + { + d_x_new_new = d_x_new_old; + this->reset_Kf(); + } + } +} + + +void Pvt_Kf::get_pv_Kf(arma::vec& p, arma::vec& v) const +{ + if (d_initialized) + { + p = d_x_new_new.subvec(0, 2); + v = d_x_new_new.subvec(3, 5); + } +} diff --git a/src/algorithms/PVT/libs/pvt_kf.h b/src/algorithms/PVT/libs/pvt_kf.h old mode 100644 new mode 100755 index 4d15c45f9..e051922ee --- a/src/algorithms/PVT/libs/pvt_kf.h +++ b/src/algorithms/PVT/libs/pvt_kf.h @@ -1,69 +1,71 @@ -/*! - * \file pvt_kf.h - * \brief Kalman Filter for Position and Velocity - * \author Javier Arribas, 2023. jarribas(at)cttc.es - * - * - * ----------------------------------------------------------------------------- - * - * GNSS-SDR is a Global Navigation Satellite System software-defined receiver. - * This file is part of GNSS-SDR. - * - * Copyright (C) 2010-2023 (see AUTHORS file for a list of contributors) - * SPDX-License-Identifier: GPL-3.0-or-later - * - * ----------------------------------------------------------------------------- - */ - -#ifndef GNSS_SDR_PVT_KF_H -#define GNSS_SDR_PVT_KF_H - -#include - -/** \addtogroup PVT - * \{ */ -/** \addtogroup PVT_libs - * \{ */ - - -/*! - * \brief Kalman Filter for Position and Velocity - * - */ -class Pvt_Kf -{ -public: - Pvt_Kf() = default; - virtual ~Pvt_Kf() = default; - void init_Kf(const arma::vec& p, - const arma::vec& v, - const arma::vec& res_p, - double solver_interval_s, - double measures_ecef_pos_sd_m, - double measures_ecef_vel_sd_ms, - double system_ecef_pos_sd_m, - double system_ecef_vel_sd_ms); - bool is_initialized() const; - void run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p); - void get_pv_Kf(arma::vec& p, arma::vec& v) const; - void reset_Kf(); - -private: - // Kalman Filter class variables - arma::mat d_F; - arma::mat d_H; - arma::mat d_R; - arma::mat d_Q; - arma::mat d_P_old_old; - arma::mat d_P_new_old; - arma::mat d_P_new_new; - arma::vec d_x_old_old; - arma::vec d_x_new_old; - arma::vec d_x_new_new; - bool d_initialized{false}; -}; - - -/** \} */ -/** \} */ -#endif // GNSS_SDR_Pvt_Kf_H +/*! + * \file pvt_kf.h + * \brief Kalman Filter for Position and Velocity + * \author Javier Arribas, 2023. jarribas(at)cttc.es + * + * + * ----------------------------------------------------------------------------- + * + * GNSS-SDR is a Global Navigation Satellite System software-defined receiver. + * This file is part of GNSS-SDR. + * + * Copyright (C) 2010-2023 (see AUTHORS file for a list of contributors) + * SPDX-License-Identifier: GPL-3.0-or-later + * + * ----------------------------------------------------------------------------- + */ + +#ifndef GNSS_SDR_PVT_KF_H +#define GNSS_SDR_PVT_KF_H + +#include + +/** \addtogroup PVT + * \{ */ +/** \addtogroup PVT_libs + * \{ */ + + +/*! + * \brief Kalman Filter for Position and Velocity + * + */ +class Pvt_Kf +{ +public: + Pvt_Kf() = default; + virtual ~Pvt_Kf() = default; + void init_Kf(const arma::vec& p, + const arma::vec& v, + const arma::vec& res_p, + double solver_interval_s, + bool estatic_measures_sd, + double measures_ecef_pos_sd_m, + double measures_ecef_vel_sd_ms, + double system_ecef_pos_sd_m, + double system_ecef_vel_sd_ms); + bool is_initialized() const; + void run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p); + void get_pv_Kf(arma::vec& p, arma::vec& v) const; + void reset_Kf(); + +private: + // Kalman Filter class variables + arma::mat d_F; + arma::mat d_H; + arma::mat d_R; + arma::mat d_Q; + arma::mat d_P_old_old; + arma::mat d_P_new_old; + arma::mat d_P_new_new; + arma::vec d_x_old_old; + arma::vec d_x_new_old; + arma::vec d_x_new_new; + bool d_initialized{false}; + bool d_static{false}; +}; + + +/** \} */ +/** \} */ +#endif // GNSS_SDR_Pvt_Kf_H diff --git a/src/algorithms/PVT/libs/rtklib_solver.cc b/src/algorithms/PVT/libs/rtklib_solver.cc old mode 100644 new mode 100755 index b85d5457c..1667eb632 --- a/src/algorithms/PVT/libs/rtklib_solver.cc +++ b/src/algorithms/PVT/libs/rtklib_solver.cc @@ -1,1779 +1,1780 @@ -/*! - * \file rtklib_solver.cc - * \brief PVT solver based on rtklib library functions adapted to the GNSS-SDR - * data flow and structures - * \authors
    - *
  • 2017-2019, Javier Arribas - *
  • 2017-2023, Carles Fernandez - *
  • 2007-2013, T. Takasu - *
- * - * This is a derived work from RTKLIB http://www.rtklib.com/ - * The original source code at https://github.com/tomojitakasu/RTKLIB is - * released under the BSD 2-clause license with an additional exclusive clause - * that does not apply here. This additional clause is reproduced below: - * - * " The software package includes some companion executive binaries or shared - * libraries necessary to execute APs on Windows. These licenses succeed to the - * original ones of these software. " - * - * Neither the executive binaries nor the shared libraries are required by, used - * or included in GNSS-SDR. - * - * ----------------------------------------------------------------------------- - * Copyright (C) 2007-2013, T. Takasu - * Copyright (C) 2017-2019, Javier Arribas - * Copyright (C) 2017-2023, Carles Fernandez - * All rights reserved. - * - * SPDX-License-Identifier: BSD-2-Clause - * - * -----------------------------------------------------------------------*/ - -#include "rtklib_solver.h" -#include "Beidou_DNAV.h" -#include "gnss_sdr_filesystem.h" -#include "rtklib_rtkpos.h" -#include "rtklib_solution.h" -#include -#include -#include -#include -#include -#include -#include - - -Rtklib_Solver::Rtklib_Solver(const rtk_t &rtk, - const std::string &dump_filename, - uint32_t type_of_rx, - bool flag_dump_to_file, - bool flag_dump_to_mat, - Pvt_Conf conf) : d_dump_filename(dump_filename), - d_rtk(rtk), - d_conf(std::move(conf)), - d_type_of_rx(type_of_rx), - d_flag_dump_enabled(flag_dump_to_file), - d_flag_dump_mat_enabled(flag_dump_to_mat) -{ - // see freq index at src/algorithms/libs/rtklib/rtklib_rtkcmn.cc - // function: satwavelen - d_rtklib_freq_index[0] = 0; - d_rtklib_freq_index[1] = 1; - d_rtklib_freq_index[2] = 2; - - d_rtklib_band_index["1G"] = 0; - d_rtklib_band_index["1C"] = 0; - d_rtklib_band_index["1B"] = 0; - d_rtklib_band_index["B1"] = 0; - d_rtklib_band_index["B3"] = 2; - d_rtklib_band_index["2G"] = 1; - d_rtklib_band_index["2S"] = 1; - d_rtklib_band_index["7X"] = 2; - d_rtklib_band_index["5X"] = 2; - d_rtklib_band_index["L5"] = 2; - d_rtklib_band_index["E6"] = 0; - - switch (d_type_of_rx) - { - case 6: // E5b only - d_rtklib_freq_index[2] = 4; - break; - case 11: // GPS L1 C/A + Galileo E5b - d_rtklib_freq_index[2] = 4; - break; - case 15: // Galileo E1B + Galileo E5b - d_rtklib_freq_index[2] = 4; - break; - case 18: // GPS L2C + Galileo E5b - d_rtklib_freq_index[2] = 4; - break; - case 19: // Galileo E5a + Galileo E5b - d_rtklib_band_index["5X"] = 0; - d_rtklib_freq_index[0] = 2; - d_rtklib_freq_index[2] = 4; - break; - case 20: // GPS L5 + Galileo E5b - d_rtklib_band_index["L5"] = 0; - d_rtklib_freq_index[0] = 2; - d_rtklib_freq_index[2] = 4; - break; - case 100: // E6B only - d_rtklib_freq_index[0] = 3; - break; - case 101: // E1 + E6B - d_rtklib_band_index["E6"] = 1; - d_rtklib_freq_index[1] = 3; - break; - case 102: // E5a + E6B - d_rtklib_band_index["E6"] = 1; - d_rtklib_freq_index[1] = 3; - break; - case 103: // E5b + E6B - d_rtklib_band_index["E6"] = 1; - d_rtklib_freq_index[1] = 3; - d_rtklib_freq_index[2] = 4; - break; - case 104: // Galileo E1B + Galileo E5a + Galileo E6B - d_rtklib_band_index["E6"] = 1; - d_rtklib_freq_index[1] = 3; - break; - case 105: // Galileo E1B + Galileo E5b + Galileo E6B - d_rtklib_freq_index[2] = 4; - d_rtklib_band_index["E6"] = 1; - d_rtklib_freq_index[1] = 3; - break; - case 106: // GPS L1 C/A + Galileo E1B + Galileo E6B - case 107: // GPS L1 C/A + Galileo E6B - d_rtklib_band_index["E6"] = 1; - d_rtklib_freq_index[1] = 3; - break; - } - // auto empty_map = std::map < int, HAS_obs_corrections >> (); - // d_has_obs_corr_map["L1 C/A"] = empty_map; - - // ############# ENABLE DATA FILE LOG ################# - if (d_flag_dump_enabled == true) - { - if (d_dump_file.is_open() == false) - { - try - { - d_dump_file.exceptions(std::ofstream::failbit | std::ofstream::badbit); - d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary); - LOG(INFO) << "PVT lib dump enabled Log file: " << d_dump_filename.c_str(); - } - catch (const std::ofstream::failure &e) - { - LOG(WARNING) << "Exception opening RTKLIB dump file " << e.what(); - } - } - } -} - - -Rtklib_Solver::~Rtklib_Solver() -{ - DLOG(INFO) << "Rtklib_Solver destructor called."; - if (d_dump_file.is_open() == true) - { - const auto pos = d_dump_file.tellp(); - try - { - d_dump_file.close(); - } - catch (const std::exception &ex) - { - LOG(WARNING) << "Exception in destructor closing the RTKLIB dump file " << ex.what(); - } - if (pos == 0) - { - errorlib::error_code ec; - if (!fs::remove(fs::path(d_dump_filename), ec)) - { - std::cerr << "Problem removing temporary file " << d_dump_filename << '\n'; - } - d_flag_dump_mat_enabled = false; - } - } - if (d_flag_dump_mat_enabled) - { - try - { - save_matfile(); - } - catch (const std::exception &ex) - { - LOG(WARNING) << "Exception in destructor saving the PVT .mat dump file " << ex.what(); - } - } -} - - -bool Rtklib_Solver::save_matfile() const -{ - // READ DUMP FILE - const std::string dump_filename = d_dump_filename; - const int32_t number_of_double_vars = 21; - const int32_t number_of_uint32_vars = 2; - const int32_t number_of_uint8_vars = 3; - const int32_t number_of_float_vars = 2; - const int32_t epoch_size_bytes = sizeof(double) * number_of_double_vars + - sizeof(uint32_t) * number_of_uint32_vars + - sizeof(uint8_t) * number_of_uint8_vars + - sizeof(float) * number_of_float_vars; - std::ifstream dump_file; - dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit); - try - { - dump_file.open(dump_filename.c_str(), std::ios::binary | std::ios::ate); - } - catch (const std::ifstream::failure &e) - { - std::cerr << "Problem opening dump file:" << e.what() << '\n'; - return false; - } - // count number of epochs and rewind - int64_t num_epoch = 0LL; - if (dump_file.is_open()) - { - std::cout << "Generating .mat file for " << dump_filename << '\n'; - const std::ifstream::pos_type size = dump_file.tellg(); - num_epoch = static_cast(size) / static_cast(epoch_size_bytes); - dump_file.seekg(0, std::ios::beg); - } - else - { - return false; - } - - auto TOW_at_current_symbol_ms = std::vector(num_epoch); - auto week = std::vector(num_epoch); - auto RX_time = std::vector(num_epoch); - auto user_clk_offset = std::vector(num_epoch); - auto pos_x = std::vector(num_epoch); - auto pos_y = std::vector(num_epoch); - auto pos_z = std::vector(num_epoch); - auto vel_x = std::vector(num_epoch); - auto vel_y = std::vector(num_epoch); - auto vel_z = std::vector(num_epoch); - auto cov_xx = std::vector(num_epoch); - auto cov_yy = std::vector(num_epoch); - auto cov_zz = std::vector(num_epoch); - auto cov_xy = std::vector(num_epoch); - auto cov_yz = std::vector(num_epoch); - auto cov_zx = std::vector(num_epoch); - auto latitude = std::vector(num_epoch); - auto longitude = std::vector(num_epoch); - auto height = std::vector(num_epoch); - auto valid_sats = std::vector(num_epoch); - auto solution_status = std::vector(num_epoch); - auto solution_type = std::vector(num_epoch); - auto AR_ratio_factor = std::vector(num_epoch); - auto AR_ratio_threshold = std::vector(num_epoch); - auto gdop = std::vector(num_epoch); - auto pdop = std::vector(num_epoch); - auto hdop = std::vector(num_epoch); - auto vdop = std::vector(num_epoch); - - try - { - if (dump_file.is_open()) - { - for (int64_t i = 0; i < num_epoch; i++) - { - dump_file.read(reinterpret_cast(&TOW_at_current_symbol_ms[i]), sizeof(uint32_t)); - dump_file.read(reinterpret_cast(&week[i]), sizeof(uint32_t)); - dump_file.read(reinterpret_cast(&RX_time[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&user_clk_offset[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&pos_x[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&pos_y[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&pos_z[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&vel_x[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&vel_y[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&vel_z[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&cov_xx[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&cov_yy[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&cov_zz[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&cov_xy[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&cov_yz[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&cov_zx[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&latitude[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&longitude[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&height[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&valid_sats[i]), sizeof(uint8_t)); - dump_file.read(reinterpret_cast(&solution_status[i]), sizeof(uint8_t)); - dump_file.read(reinterpret_cast(&solution_type[i]), sizeof(uint8_t)); - dump_file.read(reinterpret_cast(&AR_ratio_factor[i]), sizeof(float)); - dump_file.read(reinterpret_cast(&AR_ratio_threshold[i]), sizeof(float)); - dump_file.read(reinterpret_cast(&gdop[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&pdop[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&hdop[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&vdop[i]), sizeof(double)); - } - } - dump_file.close(); - } - catch (const std::ifstream::failure &e) - { - std::cerr << "Problem reading dump file:" << e.what() << '\n'; - return false; - } - - // WRITE MAT FILE - mat_t *matfp; - matvar_t *matvar; - std::string filename = dump_filename; - filename.erase(filename.length() - 4, 4); - filename.append(".mat"); - matfp = Mat_CreateVer(filename.c_str(), nullptr, MAT_FT_MAT73); - if (reinterpret_cast(matfp) != nullptr) - { - std::array dims{1, static_cast(num_epoch)}; - matvar = Mat_VarCreate("TOW_at_current_symbol_ms", MAT_C_UINT32, MAT_T_UINT32, 2, dims.data(), TOW_at_current_symbol_ms.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("week", MAT_C_UINT32, MAT_T_UINT32, 2, dims.data(), week.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("RX_time", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), RX_time.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("user_clk_offset", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), user_clk_offset.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("pos_x", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), pos_x.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("pos_y", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), pos_y.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("pos_z", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), pos_z.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("vel_x", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), vel_x.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("vel_y", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), vel_y.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("vel_z", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), vel_z.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("cov_xx", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_xx.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("cov_yy", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_yy.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("cov_zz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_zz.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("cov_xy", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_xy.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("cov_yz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_yz.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("cov_zx", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_zx.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("latitude", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), latitude.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("longitude", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), longitude.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("height", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), height.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("valid_sats", MAT_C_UINT8, MAT_T_UINT8, 2, dims.data(), valid_sats.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("solution_status", MAT_C_UINT8, MAT_T_UINT8, 2, dims.data(), solution_status.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("solution_type", MAT_C_UINT8, MAT_T_UINT8, 2, dims.data(), solution_type.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("AR_ratio_factor", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims.data(), AR_ratio_factor.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("AR_ratio_threshold", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims.data(), AR_ratio_threshold.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("gdop", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), gdop.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("pdop", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), pdop.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("hdop", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), hdop.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("vdop", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), vdop.data(), 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - } - - Mat_Close(matfp); - return true; -} - - -double Rtklib_Solver::get_gdop() const -{ - return d_dop[0]; -} - - -double Rtklib_Solver::get_pdop() const -{ - return d_dop[1]; -} - - -double Rtklib_Solver::get_hdop() const -{ - return d_dop[2]; -} - - -double Rtklib_Solver::get_vdop() const -{ - return d_dop[3]; -} - - -Monitor_Pvt Rtklib_Solver::get_monitor_pvt() const -{ - return d_monitor_pvt; -} - - -void Rtklib_Solver::store_has_data(const Galileo_HAS_data &new_has_data) -{ - // Compute time of application HAS SIS ICD, Issue 1.0, Section 7.7 - uint16_t toh = new_has_data.header.toh; - uint32_t hr = std::floor(new_has_data.tow / 3600); - uint32_t tmt = 0; - if ((hr * 3600 + toh) <= new_has_data.tow) - { - tmt = hr * 3600 + toh; - } - else - { - tmt = (hr - 1) * 3600 + toh; - } - - const std::string gps_str("GPS"); - const std::string gal_str("Galileo"); - if (new_has_data.header.orbit_correction_flag) - { - LOG(INFO) << "Received HAS orbit corrections"; - // for each satellite in GPS ephemeris - for (const auto &gpseph : gps_ephemeris_map) - { - int prn = gpseph.second.PRN; - int32_t sis_iod = gpseph.second.IODE_SF3; - uint16_t gnss_iod = new_has_data.get_gnss_iod(gps_str, prn); - if (static_cast(gnss_iod) == sis_iod) - { - float radial_m = new_has_data.get_delta_radial_m(gps_str, prn); - if (std::fabs(radial_m + 10.24) < 0.001) // -10.24 means not available - { - radial_m = 0.0; - } - float in_track_m = new_has_data.get_delta_in_track_m(gps_str, prn); - if (std::fabs(in_track_m + 16.384) < 0.001) // -16.384 means not available - { - in_track_m = 0.0; - } - float cross_track_m = new_has_data.get_delta_in_track_m(gps_str, prn); - if (std::fabs(cross_track_m + 16.384) < 0.001) // -16.384 means not available - { - cross_track_m = 0.0; - } - d_has_orbit_corrections_store_map[gps_str][prn].radial_m = radial_m; - d_has_orbit_corrections_store_map[gps_str][prn].in_track_m = in_track_m; - d_has_orbit_corrections_store_map[gps_str][prn].cross_track_m = cross_track_m; - d_has_orbit_corrections_store_map[gps_str][prn].valid_until = tmt + - new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_orbit_corrections); - d_has_orbit_corrections_store_map[gps_str][prn].iod = gnss_iod; - // TODO: check for end of week - } - } - - // for each satellite in Galileo ephemeris - for (const auto &galeph : galileo_ephemeris_map) - { - int prn = galeph.second.PRN; - int32_t sis_iod = galeph.second.IOD_ephemeris; - uint16_t gnss_iod = new_has_data.get_gnss_iod(gal_str, prn); - if (static_cast(gnss_iod) == sis_iod) - { - float radial_m = new_has_data.get_delta_radial_m(gal_str, prn); - if (std::fabs(radial_m + 10.24) < 0.001) // -10.24 means not available - { - radial_m = 0.0; - } - float in_track_m = new_has_data.get_delta_in_track_m(gal_str, prn); - if (std::fabs(in_track_m + 16.384) < 0.001) // -16.384 means not available - { - in_track_m = 0.0; - } - float cross_track_m = new_has_data.get_delta_in_track_m(gal_str, prn); - if (std::fabs(cross_track_m + 16.384) < 0.001) // -16.384 means not available - { - cross_track_m = 0.0; - } - d_has_orbit_corrections_store_map[gal_str][prn].radial_m = radial_m; - d_has_orbit_corrections_store_map[gal_str][prn].in_track_m = in_track_m; - d_has_orbit_corrections_store_map[gal_str][prn].cross_track_m = cross_track_m; - d_has_orbit_corrections_store_map[gal_str][prn].valid_until = tmt + - new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_orbit_corrections); - d_has_orbit_corrections_store_map[gal_str][prn].iod = gnss_iod; - // TODO: check for end of week - } - } - } - if (new_has_data.header.clock_fullset_flag) - { - LOG(INFO) << "Received HAS clock fullset corrections"; - for (const auto &gpseph : gps_ephemeris_map) - { - int prn = gpseph.second.PRN; - int32_t sis_iod = gpseph.second.IODE_SF3; - auto it = d_has_orbit_corrections_store_map[gps_str].find(prn); - if (it != d_has_orbit_corrections_store_map[gps_str].end()) - { - uint16_t gnss_iod = it->second.iod; - if (static_cast(gnss_iod) == sis_iod) - { - float clock_correction_mult_m = new_has_data.get_clock_correction_mult_m(gps_str, prn); - if ((std::fabs(clock_correction_mult_m + 10.24) < 0.001) || - (std::fabs(clock_correction_mult_m + 20.48) < 0.001) || - (std::fabs(clock_correction_mult_m + 30.72) < 0.001) || - (std::fabs(clock_correction_mult_m + 40.96) < 0.001)) - { - clock_correction_mult_m = 0.0; - } - if ((std::fabs(clock_correction_mult_m - 10.2375) < 0.001) || - (std::fabs(clock_correction_mult_m - 20.475) < 0.001) || - (std::fabs(clock_correction_mult_m - 30.7125) < 0.001) || - (std::fabs(clock_correction_mult_m - 40.95) < 0.001)) - { - // Satellite should not be used! - clock_correction_mult_m = 0.0; - } - d_has_clock_corrections_store_map[gps_str][prn].clock_correction_m = clock_correction_mult_m; - d_has_clock_corrections_store_map[gps_str][prn].valid_until = tmt + - new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_clock_fullset_corrections); - // TODO: check for end of week - } - } - } - - // for each satellite in Galileo ephemeris - for (const auto &galeph : galileo_ephemeris_map) - { - int prn = galeph.second.PRN; - int32_t iod_sis = galeph.second.IOD_ephemeris; - auto it = d_has_orbit_corrections_store_map[gal_str].find(prn); - if (it != d_has_orbit_corrections_store_map[gal_str].end()) - { - uint16_t gnss_iod = it->second.iod; - if (static_cast(gnss_iod) == iod_sis) - { - float clock_correction_mult_m = new_has_data.get_clock_correction_mult_m(gal_str, prn); - // std::cout << "Galileo Satellite " << prn - // << " clock correction=" << new_has_data.get_clock_correction_mult_m(gal_str, prn) - // << std::endl; - if ((std::fabs(clock_correction_mult_m + 10.24) < 0.001) || - (std::fabs(clock_correction_mult_m + 20.48) < 0.001) || - (std::fabs(clock_correction_mult_m + 30.72) < 0.001) || - (std::fabs(clock_correction_mult_m + 40.96) < 0.001)) - { - clock_correction_mult_m = 0.0; - } - d_has_clock_corrections_store_map[gal_str][prn].clock_correction_m = clock_correction_mult_m; - d_has_clock_corrections_store_map[gal_str][prn].valid_until = tmt + - new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_clock_fullset_corrections); - // TODO: check for end of week - } - } - } - } - if (new_has_data.header.clock_subset_flag) - { - LOG(INFO) << "Received HAS clock subset corrections"; - for (const auto &gpseph : gps_ephemeris_map) - { - int prn = gpseph.second.PRN; - int32_t sis_iod = gpseph.second.IODE_SF3; - int32_t gnss_iod = d_has_orbit_corrections_store_map[gps_str][prn].iod; - if (gnss_iod == sis_iod) - { - // d_has_clock_corrections_store_map[gps_str][prn].clock_correction_m = new_has_data.get_clock_subset_correction_mult_m(gps_str, prn); - // d_has_clock_corrections_store_map[gps_str][prn].valid_until = tmt + new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_clock_subset_corrections); - // TODO: check for end of week - } - } - } - if (new_has_data.header.code_bias_flag) - { - LOG(INFO) << "Received HAS code bias corrections"; - uint32_t valid_until = tmt + - new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_code_bias_corrections); - auto signals_gal = new_has_data.get_signals_in_mask(gal_str); - for (const auto &it : signals_gal) - { - auto prns = new_has_data.get_PRNs_in_mask(gal_str); - for (auto prn : prns) - { - float code_bias_m = new_has_data.get_code_bias_m(it, prn); - if ((std::fabs(code_bias_m + 20.48) < 0.01)) // -20.48 means not available - { - code_bias_m = 0.0; - } - d_has_code_bias_store_map[it][prn] = {code_bias_m, valid_until}; - } - } - auto signals_gps = new_has_data.get_signals_in_mask(gps_str); - for (const auto &it : signals_gps) - { - auto prns = new_has_data.get_PRNs_in_mask(gps_str); - for (auto prn : prns) - { - float code_bias_m = new_has_data.get_code_bias_m(it, prn); - if ((std::fabs(code_bias_m + 20.48) < 0.01)) // -20.48 means not available - { - code_bias_m = 0.0; - } - d_has_code_bias_store_map[it][prn] = {code_bias_m, valid_until}; - } - } - } - if (new_has_data.header.phase_bias_flag) - { - LOG(INFO) << "Received HAS phase bias corrections"; - uint32_t valid_until = tmt + - new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_phase_bias_corrections); - - auto signals_gal = new_has_data.get_signals_in_mask(gal_str); - for (const auto &it : signals_gal) - { - auto prns = new_has_data.get_PRNs_in_mask(gal_str); - for (auto prn : prns) - { - float phase_bias_correction_cycles = new_has_data.get_phase_bias_cycle(it, prn); - if (std::fabs(phase_bias_correction_cycles + 10.24) < 0.001) // -10.24 means not available - { - phase_bias_correction_cycles = 0.0; - } - d_has_phase_bias_store_map[it][prn] = {phase_bias_correction_cycles, valid_until}; - // TODO: process Phase Discontinuity Indicator - } - } - auto signals_gps = new_has_data.get_signals_in_mask(gps_str); - for (const auto &it : signals_gps) - { - auto prns = new_has_data.get_PRNs_in_mask(gps_str); - for (auto prn : prns) - { - float phase_bias_correction_cycles = new_has_data.get_phase_bias_cycle(it, prn); - if (std::fabs(phase_bias_correction_cycles + 10.24) < 0.001) // -10.24 means not available - { - phase_bias_correction_cycles = 0.0; - } - d_has_phase_bias_store_map[it][prn] = {phase_bias_correction_cycles, valid_until}; - // TODO: process Phase Discontinuity Indicator - } - } - } -} - - -void Rtklib_Solver::update_has_corrections(const std::map &obs_map) -{ - this->check_has_orbit_clock_validity(obs_map); - this->get_has_biases(obs_map); -} - - -void Rtklib_Solver::check_has_orbit_clock_validity(const std::map &obs_map) -{ - for (const auto &it : obs_map) - { - uint32_t obs_tow = it.second.interp_TOW_ms / 1000.0; - auto prn = static_cast(it.second.PRN); - - if (it.second.System == 'G') - { - auto it_sys = d_has_orbit_corrections_store_map.find("GPS"); - if (it_sys != d_has_orbit_corrections_store_map.end()) - { - auto it_map_corr = it_sys->second.find(prn); - if (it_map_corr != it_sys->second.end()) - { - auto has_data_valid_until = it_map_corr->second.valid_until; - if (has_data_valid_until < obs_tow) - { - // Delete outdated data - it_sys->second.erase(prn); - } - } - } - auto it_sys_clock = d_has_clock_corrections_store_map.find("GPS"); - if (it_sys_clock != d_has_clock_corrections_store_map.end()) - { - auto it_map_corr = it_sys_clock->second.find(prn); - if (it_map_corr != it_sys_clock->second.end()) - { - auto has_data_valid_until = it_map_corr->second.valid_until; - if (has_data_valid_until < obs_tow) - { - // Delete outdated data - it_sys_clock->second.erase(prn); - } - } - } - } - if (it.second.System == 'E') - { - auto it_sys = d_has_orbit_corrections_store_map.find("Galileo"); - if (it_sys != d_has_orbit_corrections_store_map.end()) - { - auto it_map_corr = it_sys->second.find(prn); - if (it_map_corr != it_sys->second.end()) - { - auto has_data_valid_until = it_map_corr->second.valid_until; - if (has_data_valid_until < obs_tow) - { - // Delete outdated data - it_sys->second.erase(prn); - } - } - } - auto it_sys_clock = d_has_clock_corrections_store_map.find("Galileo"); - if (it_sys_clock != d_has_clock_corrections_store_map.end()) - { - auto it_map_corr = it_sys_clock->second.find(prn); - if (it_map_corr != it_sys_clock->second.end()) - { - auto has_data_valid_until = it_map_corr->second.valid_until; - if (has_data_valid_until < obs_tow) - { - // Delete outdated data - it_sys_clock->second.erase(prn); - } - } - } - } - } -} - - -void Rtklib_Solver::get_has_biases(const std::map &obs_map) -{ - d_has_obs_corr_map.clear(); - if (!d_has_clock_corrections_store_map.empty() && !d_has_orbit_corrections_store_map.empty()) - { - const std::vector e1b_signals = {"E1-B I/NAV OS", "E1-C", "E1-B + E1-C"}; - const std::vector e6_signals = {"E6-B C/NAV HAS", "E6-C", "E6-B + E6-C"}; - const std::vector e5_signals = {"E5a-I F/NAV OS", "E5a-Q", "E5a-I+E5a-Q"}; - const std::vector e7_signals = {"E5bI I/NAV OS", "E5b-Q", "E5b-I+E5b-Q"}; - const std::vector g1c_signals = {"L1 C/A"}; - const std::vector g2s_signals = {"L2 CM", "L2 CL", "L2 CM+CL", "L2 P"}; - const std::vector g5_signals = {"L5 I", "L5 Q", "L5 I + L5 Q"}; - - for (const auto &it : obs_map) - { - uint32_t obs_tow = it.second.interp_TOW_ms / 1000.0; - int prn = static_cast(it.second.PRN); - std::string sig(it.second.Signal, 2); - if (it.second.System == 'E') - { - auto it_sys_clock = d_has_clock_corrections_store_map.find("Galileo"); - if (it_sys_clock != d_has_clock_corrections_store_map.end()) - { - auto it_map_corr = it_sys_clock->second.find(prn); - if (it_map_corr != it_sys_clock->second.end()) - { - if (sig == "1B") - { - for (const auto &has_signal : e1b_signals) - { - this->get_current_has_obs_correction(has_signal, obs_tow, prn); - } - } - else if (sig == "E6") - { - for (const auto &has_signal : e6_signals) - { - this->get_current_has_obs_correction(has_signal, obs_tow, prn); - } - } - else if (sig == "5X") - { - for (const auto &has_signal : e5_signals) - { - this->get_current_has_obs_correction(has_signal, obs_tow, prn); - } - } - else if (sig == "7X") - { - for (const auto &has_signal : e7_signals) - { - this->get_current_has_obs_correction(has_signal, obs_tow, prn); - } - } - } - } - } - if (it.second.System == 'G') - { - auto it_sys_clock = d_has_clock_corrections_store_map.find("GPS"); - if (it_sys_clock != d_has_clock_corrections_store_map.end()) - { - auto it_map_corr = it_sys_clock->second.find(prn); - if (it_map_corr != it_sys_clock->second.end()) - { - if (sig == "1C") - { - for (const auto &has_signal : g1c_signals) - { - this->get_current_has_obs_correction(has_signal, obs_tow, prn); - } - } - else if (sig == "2S") - { - for (const auto &has_signal : g2s_signals) - { - this->get_current_has_obs_correction(has_signal, obs_tow, prn); - } - } - else if (sig == "L5") - { - for (const auto &has_signal : g5_signals) - { - this->get_current_has_obs_correction(has_signal, obs_tow, prn); - } - } - } - } - } - } - } -} - - -void Rtklib_Solver::get_current_has_obs_correction(const std::string &signal, uint32_t tow_obs, int prn) -{ - auto code_bias_pair_it = this->d_has_code_bias_store_map[signal].find(prn); - if (code_bias_pair_it != this->d_has_code_bias_store_map[signal].end()) - { - uint32_t valid_until = code_bias_pair_it->second.second; - if (valid_until > tow_obs) - { - this->d_has_obs_corr_map[signal][prn].code_bias_m = code_bias_pair_it->second.first; - } - } - auto phase_bias_pair_it = this->d_has_phase_bias_store_map[signal].find(prn); - if (phase_bias_pair_it != this->d_has_phase_bias_store_map[signal].end()) - { - uint32_t valid_until = phase_bias_pair_it->second.second; - if (valid_until > tow_obs) - { - this->d_has_obs_corr_map[signal][prn].phase_bias_cycle = phase_bias_pair_it->second.first; - } - } -} - - -bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_map, double kf_update_interval_s) -{ - std::map::const_iterator gnss_observables_iter; - std::map::const_iterator galileo_ephemeris_iter; - std::map::const_iterator gps_ephemeris_iter; - std::map::const_iterator gps_cnav_ephemeris_iter; - std::map::const_iterator glonass_gnav_ephemeris_iter; - std::map::const_iterator beidou_ephemeris_iter; - - const Glonass_Gnav_Utc_Model &gnav_utc = this->glonass_gnav_utc_model; - - // ******************************************************************************** - // ****** PREPARE THE DATA (SV EPHEMERIS AND OBSERVATIONS) ************************ - // ******************************************************************************** - int valid_obs = 0; // valid observations counter - int glo_valid_obs = 0; // GLONASS L1/L2 valid observations counter - - d_obs_data.fill({}); - std::vector eph_data(MAXOBS); - std::vector geph_data(MAXOBS); - - // Workaround for NAV/CNAV clash problem - bool gps_dual_band = false; - bool band1 = false; - bool band2 = false; - - for (gnss_observables_iter = gnss_observables_map.cbegin(); - gnss_observables_iter != gnss_observables_map.cend(); - ++gnss_observables_iter) - { - switch (gnss_observables_iter->second.System) - { - case 'G': - { - const std::string sig_(gnss_observables_iter->second.Signal, 2); - if (sig_ == "1C") - { - band1 = true; - } - if (sig_ == "2S") - { - band2 = true; - } - } - break; - default: - { - } - } - } - if (band1 == true and band2 == true) - { - gps_dual_band = true; - } - - for (gnss_observables_iter = gnss_observables_map.cbegin(); - gnss_observables_iter != gnss_observables_map.cend(); - ++gnss_observables_iter) // CHECK INCONSISTENCY when combining GLONASS + other system - { - switch (gnss_observables_iter->second.System) - { - case 'E': - { - const std::string gal_str("Galileo"); - const std::string sig_(gnss_observables_iter->second.Signal, 2); - // Galileo E1 - if (sig_ == "1B") - { - // 1 Gal - find the ephemeris for the current GALILEO SV observation. The SV PRN ID is the map key - galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (galileo_ephemeris_iter != galileo_ephemeris_map.cend()) - { - // convert ephemeris from GNSS-SDR class to RTKLIB structure - eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second, - this->d_has_orbit_corrections_store_map[gal_str], - this->d_has_clock_corrections_store_map[gal_str]); - // convert observation from GNSS-SDR class to RTKLIB structure - obsd_t newobs{}; - d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, - gnss_observables_iter->second, - d_has_obs_corr_map, - galileo_ephemeris_iter->second.WN, - d_rtklib_band_index[sig_]); - valid_obs++; - } - else // the ephemeris are not available for this SV - { - DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; - } - } - - // Galileo E5 - if ((sig_ == "5X") || (sig_ == "7X")) - { - // 1 Gal - find the ephemeris for the current GALILEO SV observation. The SV PRN ID is the map key - galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (galileo_ephemeris_iter != galileo_ephemeris_map.cend()) - { - bool found_E1_obs = false; - for (int i = 0; i < valid_obs; i++) - { - if (eph_data[i].sat == (static_cast(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO))) - { - d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs], - gnss_observables_iter->second, - d_has_obs_corr_map, - galileo_ephemeris_iter->second.WN, - d_rtklib_band_index[sig_]); - found_E1_obs = true; - break; - } - } - if (!found_E1_obs) - { - // insert Galileo E5 obs as new obs and also insert its ephemeris - // convert ephemeris from GNSS-SDR class to RTKLIB structure - eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second, - this->d_has_orbit_corrections_store_map[gal_str], - this->d_has_clock_corrections_store_map[gal_str]); - // convert observation from GNSS-SDR class to RTKLIB structure - const auto default_code_ = static_cast(CODE_NONE); - obsd_t newobs = {{0, 0}, '0', '0', {}, {}, - {default_code_, default_code_, default_code_}, - {}, {0.0, 0.0, 0.0}, {}}; - d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, - gnss_observables_iter->second, - d_has_obs_corr_map, - galileo_ephemeris_iter->second.WN, - d_rtklib_band_index[sig_]); - valid_obs++; - } - } - else // the ephemeris are not available for this SV - { - DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; - } - } - if (sig_ == "E6" && d_conf.use_e6_for_pvt) - { - galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (galileo_ephemeris_iter != galileo_ephemeris_map.cend()) - { - bool found_E1_obs = false; - for (int i = 0; i < valid_obs; i++) - { - if (eph_data[i].sat == (static_cast(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO))) - { - d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs], - gnss_observables_iter->second, - d_has_obs_corr_map, - galileo_ephemeris_iter->second.WN, - d_rtklib_band_index[sig_]); - found_E1_obs = true; - break; - } - } - if (!found_E1_obs) - { - // insert Galileo E6 obs as new obs and also insert its ephemeris - // convert ephemeris from GNSS-SDR class to RTKLIB structure - eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second, - this->d_has_orbit_corrections_store_map[gal_str], - this->d_has_clock_corrections_store_map[gal_str]); - // convert observation from GNSS-SDR class to RTKLIB structure - const auto default_code_ = static_cast(CODE_NONE); - obsd_t newobs = {{0, 0}, '0', '0', {}, {}, - {default_code_, default_code_, default_code_}, - {}, {0.0, 0.0, 0.0}, {}}; - d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, - gnss_observables_iter->second, - d_has_obs_corr_map, - galileo_ephemeris_iter->second.WN, - d_rtklib_band_index[sig_]); - valid_obs++; - } - } - else // the ephemeris are not available for this SV - { - DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; - } - } - if (sig_ == "E6") - { - galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (galileo_ephemeris_iter != galileo_ephemeris_map.cend()) - { - bool found_E1_obs = false; - for (int i = 0; i < valid_obs; i++) - { - if (eph_data[i].sat == (static_cast(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO))) - { - d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs], - gnss_observables_iter->second, - galileo_ephemeris_iter->second.WN, - 2); // Band E6 - found_E1_obs = true; - break; - } - } - if (!found_E1_obs) - { - // insert Galileo E6 obs as new obs and also insert its ephemeris - // convert ephemeris from GNSS-SDR class to RTKLIB structure - eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second); - // convert observation from GNSS-SDR class to RTKLIB structure - const auto default_code_ = static_cast(CODE_NONE); - obsd_t newobs = {{0, 0}, '0', '0', {}, {}, - {default_code_, default_code_, default_code_}, - {}, {0.0, 0.0, 0.0}, {}}; - d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, - gnss_observables_iter->second, - galileo_ephemeris_iter->second.WN, - 2); // Band E6 - // std::cout << "Week " << galileo_ephemeris_iter->second.WN << '\n'; - valid_obs++; - } - } - else // the ephemeris are not available for this SV - { - DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; - } - } - break; - } - case 'G': - { - // GPS L1 - // 1 GPS - find the ephemeris for the current GPS SV observation. The SV PRN ID is the map key - const std::string gps_str("GPS"); - const std::string sig_(gnss_observables_iter->second.Signal, 2); - if (sig_ == "1C") - { - gps_ephemeris_iter = gps_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (gps_ephemeris_iter != gps_ephemeris_map.cend()) - { - // convert ephemeris from GNSS-SDR class to RTKLIB structure - eph_data[valid_obs] = eph_to_rtklib(gps_ephemeris_iter->second, - this->d_has_orbit_corrections_store_map[gps_str], - this->d_has_clock_corrections_store_map[gps_str], - this->is_pre_2009()); - // convert observation from GNSS-SDR class to RTKLIB structure - obsd_t newobs{}; - d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, - gnss_observables_iter->second, - d_has_obs_corr_map, - gps_ephemeris_iter->second.WN, - d_rtklib_band_index[sig_], - this->is_pre_2009()); - valid_obs++; - } - else // the ephemeris are not available for this SV - { - DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->first; - } - } - // GPS L2 (todo: solve NAV/CNAV clash) - if ((sig_ == "2S") and (gps_dual_band == false)) - { - gps_cnav_ephemeris_iter = gps_cnav_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (gps_cnav_ephemeris_iter != gps_cnav_ephemeris_map.cend()) - { - // 1. Find the same satellite in GPS L1 band - gps_ephemeris_iter = gps_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (gps_ephemeris_iter != gps_ephemeris_map.cend()) - { - /* By the moment, GPS L2 observables are not used in pseudorange computations if GPS L1 is available - // 2. If found, replace the existing GPS L1 ephemeris with the GPS L2 ephemeris - // (more precise!), and attach the L2 observation to the L1 observation in RTKLIB structure - for (int i = 0; i < valid_obs; i++) - { - if (eph_data[i].sat == static_cast(gnss_observables_iter->second.PRN)) - { - eph_data[i] = eph_to_rtklib(gps_cnav_ephemeris_iter->second); - d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs], - gnss_observables_iter->second, - eph_data[i].week, - d_rtklib_band_index[sig_]); - break; - } - } - */ - } - else - { - // 3. If not found, insert the GPS L2 ephemeris and the observation - // convert ephemeris from GNSS-SDR class to RTKLIB structure - eph_data[valid_obs] = eph_to_rtklib(gps_cnav_ephemeris_iter->second); - // convert observation from GNSS-SDR class to RTKLIB structure - const auto default_code_ = static_cast(CODE_NONE); - obsd_t newobs = {{0, 0}, '0', '0', {}, {}, - {default_code_, default_code_, default_code_}, - {}, {0.0, 0.0, 0.0}, {}}; - d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, - gnss_observables_iter->second, - gps_cnav_ephemeris_iter->second.WN, - d_rtklib_band_index[sig_]); - valid_obs++; - } - } - else // the ephemeris are not available for this SV - { - DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; - } - } - // GPS L5 - if (sig_ == "L5") - { - gps_cnav_ephemeris_iter = gps_cnav_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (gps_cnav_ephemeris_iter != gps_cnav_ephemeris_map.cend()) - { - // 1. Find the same satellite in GPS L1 band - gps_ephemeris_iter = gps_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (gps_ephemeris_iter != gps_ephemeris_map.cend()) - { - // 2. If found, replace the existing GPS L1 ephemeris with the GPS L5 ephemeris - // (more precise!), and attach the L5 observation to the L1 observation in RTKLIB structure - for (int i = 0; i < valid_obs; i++) - { - if (eph_data[i].sat == static_cast(gnss_observables_iter->second.PRN)) - { - eph_data[i] = eph_to_rtklib(gps_cnav_ephemeris_iter->second); - d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i], - gnss_observables_iter->second, - gps_cnav_ephemeris_iter->second.WN, - d_rtklib_band_index[sig_]); - break; - } - } - } - else - { - // 3. If not found, insert the GPS L5 ephemeris and the observation - // convert ephemeris from GNSS-SDR class to RTKLIB structure - eph_data[valid_obs] = eph_to_rtklib(gps_cnav_ephemeris_iter->second); - // convert observation from GNSS-SDR class to RTKLIB structure - const auto default_code_ = static_cast(CODE_NONE); - obsd_t newobs = {{0, 0}, '0', '0', {}, {}, - {default_code_, default_code_, default_code_}, - {}, {0.0, 0.0, 0.0}, {}}; - d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, - gnss_observables_iter->second, - d_has_obs_corr_map, - gps_cnav_ephemeris_iter->second.WN, - d_rtklib_band_index[sig_]); - valid_obs++; - } - } - else // the ephemeris are not available for this SV - { - DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; - } - } - break; - } - case 'R': // TODO This should be using rtk lib nomenclature - { - const std::string sig_(gnss_observables_iter->second.Signal); - // GLONASS GNAV L1 - if (sig_ == "1G") - { - // 1 Glo - find the ephemeris for the current GLONASS SV observation. The SV Slot Number (PRN ID) is the map key - glonass_gnav_ephemeris_iter = glonass_gnav_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (glonass_gnav_ephemeris_iter != glonass_gnav_ephemeris_map.cend()) - { - // convert ephemeris from GNSS-SDR class to RTKLIB structure - geph_data[glo_valid_obs] = eph_to_rtklib(glonass_gnav_ephemeris_iter->second, gnav_utc); - // convert observation from GNSS-SDR class to RTKLIB structure - obsd_t newobs{}; - d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, - gnss_observables_iter->second, - glonass_gnav_ephemeris_iter->second.d_WN, - d_rtklib_band_index[sig_]); - glo_valid_obs++; - } - else // the ephemeris are not available for this SV - { - DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; - } - } - // GLONASS GNAV L2 - if (sig_ == "2G") - { - // 1 GLONASS - find the ephemeris for the current GLONASS SV observation. The SV PRN ID is the map key - glonass_gnav_ephemeris_iter = glonass_gnav_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (glonass_gnav_ephemeris_iter != glonass_gnav_ephemeris_map.cend()) - { - bool found_L1_obs = false; - for (int i = 0; i < glo_valid_obs; i++) - { - if (geph_data[i].sat == (static_cast(gnss_observables_iter->second.PRN + NSATGPS))) - { - d_obs_data[i + valid_obs] = insert_obs_to_rtklib(d_obs_data[i + valid_obs], - gnss_observables_iter->second, - glonass_gnav_ephemeris_iter->second.d_WN, - d_rtklib_band_index[sig_]); - found_L1_obs = true; - break; - } - } - if (!found_L1_obs) - { - // insert GLONASS GNAV L2 obs as new obs and also insert its ephemeris - // convert ephemeris from GNSS-SDR class to RTKLIB structure - geph_data[glo_valid_obs] = eph_to_rtklib(glonass_gnav_ephemeris_iter->second, gnav_utc); - // convert observation from GNSS-SDR class to RTKLIB structure - obsd_t newobs{}; - d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, - gnss_observables_iter->second, - glonass_gnav_ephemeris_iter->second.d_WN, - d_rtklib_band_index[sig_]); - glo_valid_obs++; - } - } - else // the ephemeris are not available for this SV - { - DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; - } - } - break; - } - case 'C': - { - // BEIDOU B1I - // - find the ephemeris for the current BEIDOU SV observation. The SV PRN ID is the map key - const std::string sig_(gnss_observables_iter->second.Signal); - if (sig_ == "B1") - { - beidou_ephemeris_iter = beidou_dnav_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (beidou_ephemeris_iter != beidou_dnav_ephemeris_map.cend()) - { - // convert ephemeris from GNSS-SDR class to RTKLIB structure - eph_data[valid_obs] = eph_to_rtklib(beidou_ephemeris_iter->second); - // convert observation from GNSS-SDR class to RTKLIB structure - obsd_t newobs{}; - d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, - gnss_observables_iter->second, - beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET, - d_rtklib_band_index[sig_]); - valid_obs++; - } - else // the ephemeris are not available for this SV - { - DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->first; - } - } - // BeiDou B3 - if (sig_ == "B3") - { - beidou_ephemeris_iter = beidou_dnav_ephemeris_map.find(gnss_observables_iter->second.PRN); - if (beidou_ephemeris_iter != beidou_dnav_ephemeris_map.cend()) - { - bool found_B1I_obs = false; - for (int i = 0; i < valid_obs; i++) - { - if (eph_data[i].sat == (static_cast(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO + NSATGAL + NSATQZS))) - { - d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs], - gnss_observables_iter->second, - beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET, - d_rtklib_band_index[sig_]); - found_B1I_obs = true; - break; - } - } - if (!found_B1I_obs) - { - // insert BeiDou B3I obs as new obs and also insert its ephemeris - // convert ephemeris from GNSS-SDR class to RTKLIB structure - eph_data[valid_obs] = eph_to_rtklib(beidou_ephemeris_iter->second); - // convert observation from GNSS-SDR class to RTKLIB structure - const auto default_code_ = static_cast(CODE_NONE); - obsd_t newobs = {{0, 0}, '0', '0', {}, {}, - {default_code_, default_code_, default_code_}, - {}, {0.0, 0.0, 0.0}, {}}; - d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, - gnss_observables_iter->second, - beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET, - d_rtklib_band_index[sig_]); - valid_obs++; - } - } - else // the ephemeris are not available for this SV - { - DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; - } - } - break; - } - - default: - DLOG(INFO) << "Hybrid observables: Unknown GNSS"; - break; - } - } - - // ********************************************************************** - // ****** SOLVE PVT****************************************************** - // ********************************************************************** - - this->set_valid_position(false); - if ((valid_obs + glo_valid_obs) > 3) - { - int result = 0; - d_nav_data = {}; - d_nav_data.eph = eph_data.data(); - d_nav_data.geph = geph_data.data(); - d_nav_data.n = valid_obs; - d_nav_data.ng = glo_valid_obs; - if (gps_iono.valid) - { - d_nav_data.ion_gps[0] = gps_iono.alpha0; - d_nav_data.ion_gps[1] = gps_iono.alpha1; - d_nav_data.ion_gps[2] = gps_iono.alpha2; - d_nav_data.ion_gps[3] = gps_iono.alpha3; - d_nav_data.ion_gps[4] = gps_iono.beta0; - d_nav_data.ion_gps[5] = gps_iono.beta1; - d_nav_data.ion_gps[6] = gps_iono.beta2; - d_nav_data.ion_gps[7] = gps_iono.beta3; - } - if (!(gps_iono.valid) and gps_cnav_iono.valid) - { - d_nav_data.ion_gps[0] = gps_cnav_iono.alpha0; - d_nav_data.ion_gps[1] = gps_cnav_iono.alpha1; - d_nav_data.ion_gps[2] = gps_cnav_iono.alpha2; - d_nav_data.ion_gps[3] = gps_cnav_iono.alpha3; - d_nav_data.ion_gps[4] = gps_cnav_iono.beta0; - d_nav_data.ion_gps[5] = gps_cnav_iono.beta1; - d_nav_data.ion_gps[6] = gps_cnav_iono.beta2; - d_nav_data.ion_gps[7] = gps_cnav_iono.beta3; - } - if (galileo_iono.ai0 != 0.0) - { - d_nav_data.ion_gal[0] = galileo_iono.ai0; - d_nav_data.ion_gal[1] = galileo_iono.ai1; - d_nav_data.ion_gal[2] = galileo_iono.ai2; - d_nav_data.ion_gal[3] = 0.0; - } - if (beidou_dnav_iono.valid) - { - d_nav_data.ion_cmp[0] = beidou_dnav_iono.alpha0; - d_nav_data.ion_cmp[1] = beidou_dnav_iono.alpha1; - d_nav_data.ion_cmp[2] = beidou_dnav_iono.alpha2; - d_nav_data.ion_cmp[3] = beidou_dnav_iono.alpha3; - d_nav_data.ion_cmp[4] = beidou_dnav_iono.beta0; - d_nav_data.ion_cmp[5] = beidou_dnav_iono.beta0; - d_nav_data.ion_cmp[6] = beidou_dnav_iono.beta0; - d_nav_data.ion_cmp[7] = beidou_dnav_iono.beta3; - } - if (gps_utc_model.valid) - { - d_nav_data.utc_gps[0] = gps_utc_model.A0; - d_nav_data.utc_gps[1] = gps_utc_model.A1; - d_nav_data.utc_gps[2] = gps_utc_model.tot; - d_nav_data.utc_gps[3] = gps_utc_model.WN_T; - d_nav_data.leaps = gps_utc_model.DeltaT_LS; - } - if (!(gps_utc_model.valid) and gps_cnav_utc_model.valid) - { - d_nav_data.utc_gps[0] = gps_cnav_utc_model.A0; - d_nav_data.utc_gps[1] = gps_cnav_utc_model.A1; - d_nav_data.utc_gps[2] = gps_cnav_utc_model.tot; - d_nav_data.utc_gps[3] = gps_cnav_utc_model.WN_T; - d_nav_data.leaps = gps_cnav_utc_model.DeltaT_LS; - } - if (glonass_gnav_utc_model.valid) - { - d_nav_data.utc_glo[0] = glonass_gnav_utc_model.d_tau_c; // ?? - d_nav_data.utc_glo[1] = 0.0; // ?? - d_nav_data.utc_glo[2] = 0.0; // ?? - d_nav_data.utc_glo[3] = 0.0; // ?? - } - if (galileo_utc_model.A0 != 0.0) - { - d_nav_data.utc_gal[0] = galileo_utc_model.A0; - d_nav_data.utc_gal[1] = galileo_utc_model.A1; - d_nav_data.utc_gal[2] = galileo_utc_model.tot; - d_nav_data.utc_gal[3] = galileo_utc_model.WNot; - d_nav_data.leaps = galileo_utc_model.Delta_tLS; - } - if (beidou_dnav_utc_model.valid) - { - d_nav_data.utc_cmp[0] = beidou_dnav_utc_model.A0_UTC; - d_nav_data.utc_cmp[1] = beidou_dnav_utc_model.A1_UTC; - d_nav_data.utc_cmp[2] = 0.0; // ?? - d_nav_data.utc_cmp[3] = 0.0; // ?? - d_nav_data.leaps = beidou_dnav_utc_model.DeltaT_LS; - } - - /* update carrier wave length using native function call in RTKlib */ - for (int i = 0; i < MAXSAT; i++) - { - for (int j = 0; j < NFREQ; j++) - { - d_nav_data.lam[i][j] = satwavelen(i + 1, d_rtklib_freq_index[j], &d_nav_data); - } - } - - result = rtkpos(&d_rtk, d_obs_data.data(), valid_obs + glo_valid_obs, &d_nav_data); - - if (result == 0) - { - LOG(INFO) << "RTKLIB rtkpos error: " << d_rtk.errbuf; - d_rtk.neb = 0; // clear error buffer to avoid repeating the error message - this->set_time_offset_s(0.0); // reset rx time estimation - this->set_num_valid_observations(0); - if (d_conf.enable_pvt_kf == true) - { - d_pvt_kf.reset_Kf(); - } - } - else - { - this->set_num_valid_observations(d_rtk.sol.ns); // record the number of valid satellites used by the PVT solver - pvt_sol = d_rtk.sol; - // DOP computation - unsigned int used_sats = 0; - for (unsigned int i = 0; i < MAXSAT; i++) - { - pvt_ssat[i] = d_rtk.ssat[i]; - if (d_rtk.ssat[i].vs == 1) - { - used_sats++; - } - } - - std::vector azel(used_sats * 2); - int index_aux = 0; - for (auto &i : d_rtk.ssat) - { - if (i.vs == 1) - { - azel[2 * index_aux] = i.azel[0]; - azel[2 * index_aux + 1] = i.azel[1]; - index_aux++; - } - } - - if (index_aux > 0) - { - dops(index_aux, azel.data(), 0.0, d_dop.data()); - } - this->set_valid_position(true); - std::array rx_position_and_time{}; - - if (d_conf.enable_pvt_kf == true) - { - if (d_pvt_kf.is_initialized() == false) - { - arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; - arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; - arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], - pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; - - d_pvt_kf.init_Kf(p, - v, - res_p, - kf_update_interval_s, - d_conf.measures_ecef_pos_sd_m, - d_conf.measures_ecef_vel_sd_ms, - d_conf.system_ecef_pos_sd_m, - d_conf.system_ecef_vel_sd_ms); - } - else - { - arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; - arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; - arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], - pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; - - d_pvt_kf.run_Kf(p, v, res_p); - d_pvt_kf.get_pv_Kf(p, v); - pvt_sol.rr[0] = p[0]; // [m] - pvt_sol.rr[1] = p[1]; // [m] - pvt_sol.rr[2] = p[2]; // [m] - pvt_sol.rr[3] = v[0]; // [ms] - pvt_sol.rr[4] = v[1]; // [ms] - pvt_sol.rr[5] = v[2]; // [ms] - } - } - - rx_position_and_time[0] = pvt_sol.rr[0]; // [m] - rx_position_and_time[1] = pvt_sol.rr[1]; // [m] - rx_position_and_time[2] = pvt_sol.rr[2]; // [m] - - // todo: fix this ambiguity in the RTKLIB units in receiver clock offset! - if (d_rtk.opt.mode == PMODE_SINGLE) - { - // if the RTKLIB solver is set to SINGLE, the dtr is already expressed in [s] - // add also the clock offset from gps to galileo (pvt_sol.dtr[2]) - rx_position_and_time[3] = pvt_sol.dtr[0] + pvt_sol.dtr[2]; - } - else - { - // the receiver clock offset is expressed in [meters], so we convert it into [s] - // add also the clock offset from gps to galileo (pvt_sol.dtr[2]) - rx_position_and_time[3] = pvt_sol.dtr[2] + pvt_sol.dtr[0] / SPEED_OF_LIGHT_M_S; - } - this->set_rx_pos({rx_position_and_time[0], rx_position_and_time[1], rx_position_and_time[2]}); // save ECEF position for the next iteration - - // compute Ground speed and COG - double ground_speed_ms = 0.0; - std::array pos{}; - std::array enuv{}; - ecef2pos(pvt_sol.rr, pos.data()); - ecef2enu(pos.data(), &pvt_sol.rr[3], enuv.data()); - this->set_speed_over_ground(norm_rtk(enuv.data(), 2)); - double new_cog; - if (ground_speed_ms >= 1.0) - { - new_cog = atan2(enuv[0], enuv[1]) * R2D; - if (new_cog < 0.0) - { - new_cog += 360.0; - } - this->set_course_over_ground(new_cog); - } - - this->set_time_offset_s(rx_position_and_time[3]); - - DLOG(INFO) << "RTKLIB Position at RX TOW = " << gnss_observables_map.cbegin()->second.RX_time - << " in ECEF (X,Y,Z,t[meters]) = " << rx_position_and_time[0] << ", " << rx_position_and_time[1] << ", " << rx_position_and_time[2] << ", " << rx_position_and_time[3]; - - // gtime_t rtklib_utc_time = gpst2utc(pvt_sol.time); // Corrected RX Time (Non integer multiply of 1 ms of granularity) - // Uncorrected RX Time (integer multiply of 1 ms and the same observables time reported in RTCM and RINEX) - const gtime_t rtklib_time = timeadd(pvt_sol.time, rx_position_and_time[3]); // uncorrected rx time - const gtime_t rtklib_utc_time = gpst2utc(rtklib_time); - boost::posix_time::ptime p_time = boost::posix_time::from_time_t(rtklib_utc_time.time); - p_time += boost::posix_time::microseconds(static_cast(round(rtklib_utc_time.sec * 1e6))); // NOLINT(google-runtime-int) - - this->set_position_UTC_time(p_time); - - DLOG(INFO) << "RTKLIB Position at " << boost::posix_time::to_simple_string(p_time) - << " is Lat = " << this->get_latitude() << " [deg], Long = " << this->get_longitude() - << " [deg], Height= " << this->get_height() << " [m]" - << " RX time offset= " << this->get_time_offset_s() << " [s]"; - - // ######## PVT MONITOR ######### - // TOW - d_monitor_pvt.TOW_at_current_symbol_ms = gnss_observables_map.cbegin()->second.TOW_at_current_symbol_ms; - // WEEK - d_monitor_pvt.week = adjgpsweek(d_nav_data.eph[0].week, this->is_pre_2009()); - // PVT GPS time - d_monitor_pvt.RX_time = gnss_observables_map.cbegin()->second.RX_time; - // User clock offset [s] - d_monitor_pvt.user_clk_offset = rx_position_and_time[3]; - - // ECEF POS X,Y,X [m] + ECEF VEL X,Y,X [m/s] (6 x double) - d_monitor_pvt.pos_x = pvt_sol.rr[0]; - d_monitor_pvt.pos_y = pvt_sol.rr[1]; - d_monitor_pvt.pos_z = pvt_sol.rr[2]; - d_monitor_pvt.vel_x = pvt_sol.rr[3]; - d_monitor_pvt.vel_y = pvt_sol.rr[4]; - d_monitor_pvt.vel_z = pvt_sol.rr[5]; - - // position variance/covariance (m^2) {c_xx,c_yy,c_zz,c_xy,c_yz,c_zx} (6 x double) - d_monitor_pvt.cov_xx = pvt_sol.qr[0]; - d_monitor_pvt.cov_yy = pvt_sol.qr[1]; - d_monitor_pvt.cov_zz = pvt_sol.qr[2]; - d_monitor_pvt.cov_xy = pvt_sol.qr[3]; - d_monitor_pvt.cov_yz = pvt_sol.qr[4]; - d_monitor_pvt.cov_zx = pvt_sol.qr[5]; - - // GEO user position Latitude [deg] - d_monitor_pvt.latitude = this->get_latitude(); - // GEO user position Longitude [deg] - d_monitor_pvt.longitude = this->get_longitude(); - // GEO user position Height [m] - d_monitor_pvt.height = this->get_height(); - - // NUMBER OF VALID SATS - d_monitor_pvt.valid_sats = pvt_sol.ns; - // RTKLIB solution status - d_monitor_pvt.solution_status = pvt_sol.stat; - // RTKLIB solution type (0:xyz-ecef,1:enu-baseline) - d_monitor_pvt.solution_type = pvt_sol.type; - // AR ratio factor for validation - d_monitor_pvt.AR_ratio_factor = pvt_sol.ratio; - // AR ratio threshold for validation - d_monitor_pvt.AR_ratio_threshold = pvt_sol.thres; - - // GDOP / PDOP/ HDOP/ VDOP - d_monitor_pvt.gdop = d_dop[0]; - d_monitor_pvt.pdop = d_dop[1]; - d_monitor_pvt.hdop = d_dop[2]; - d_monitor_pvt.vdop = d_dop[3]; - - this->set_rx_vel({enuv[0], enuv[1], enuv[2]}); - - const double clock_drift_ppm = pvt_sol.dtr[5] / SPEED_OF_LIGHT_M_S * 1e6; - - this->set_clock_drift_ppm(clock_drift_ppm); - // User clock drift [ppm] - d_monitor_pvt.user_clk_drift_ppm = clock_drift_ppm; - - // ######## LOG FILE ######### - if (d_flag_dump_enabled == true) - { - // MULTIPLEXED FILE RECORDING - Record results to file - try - { - double tmp_double; - uint32_t tmp_uint32; - // TOW - tmp_uint32 = gnss_observables_map.cbegin()->second.TOW_at_current_symbol_ms; - d_dump_file.write(reinterpret_cast(&tmp_uint32), sizeof(uint32_t)); - // WEEK - tmp_uint32 = adjgpsweek(d_nav_data.eph[0].week, this->is_pre_2009()); - d_dump_file.write(reinterpret_cast(&tmp_uint32), sizeof(uint32_t)); - // PVT GPS time - tmp_double = gnss_observables_map.cbegin()->second.RX_time; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - // User clock offset [s] - tmp_double = rx_position_and_time[3]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - - // ECEF POS X,Y,X [m] + ECEF VEL X,Y,X [m/s] (6 x double) - tmp_double = pvt_sol.rr[0]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - tmp_double = pvt_sol.rr[1]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - tmp_double = pvt_sol.rr[2]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - tmp_double = pvt_sol.rr[3]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - tmp_double = pvt_sol.rr[4]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - tmp_double = pvt_sol.rr[5]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - - // position variance/covariance (m^2) {c_xx,c_yy,c_zz,c_xy,c_yz,c_zx} (6 x double) - tmp_double = pvt_sol.qr[0]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - tmp_double = pvt_sol.qr[1]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - tmp_double = pvt_sol.qr[2]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - tmp_double = pvt_sol.qr[3]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - tmp_double = pvt_sol.qr[4]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - tmp_double = pvt_sol.qr[5]; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - - // GEO user position Latitude [deg] - tmp_double = this->get_latitude(); - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - // GEO user position Longitude [deg] - tmp_double = this->get_longitude(); - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - // GEO user position Height [m] - tmp_double = this->get_height(); - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - - // NUMBER OF VALID SATS - d_dump_file.write(reinterpret_cast(&pvt_sol.ns), sizeof(uint8_t)); - // RTKLIB solution status - d_dump_file.write(reinterpret_cast(&pvt_sol.stat), sizeof(uint8_t)); - // RTKLIB solution type (0:xyz-ecef,1:enu-baseline) - d_dump_file.write(reinterpret_cast(&pvt_sol.type), sizeof(uint8_t)); - // AR ratio factor for validation - d_dump_file.write(reinterpret_cast(&pvt_sol.ratio), sizeof(float)); - // AR ratio threshold for validation - d_dump_file.write(reinterpret_cast(&pvt_sol.thres), sizeof(float)); - - // GDOP / PDOP / HDOP / VDOP - d_dump_file.write(reinterpret_cast(&d_dop[0]), sizeof(double)); - d_dump_file.write(reinterpret_cast(&d_dop[1]), sizeof(double)); - d_dump_file.write(reinterpret_cast(&d_dop[2]), sizeof(double)); - d_dump_file.write(reinterpret_cast(&d_dop[3]), sizeof(double)); - } - catch (const std::ofstream::failure &e) - { - LOG(WARNING) << "Exception writing RTKLIB dump file " << e.what(); - } - } - } - } - return this->is_valid_position(); -} +/*! + * \file rtklib_solver.cc + * \brief PVT solver based on rtklib library functions adapted to the GNSS-SDR + * data flow and structures + * \authors
    + *
  • 2017-2019, Javier Arribas + *
  • 2017-2023, Carles Fernandez + *
  • 2007-2013, T. Takasu + *
+ * + * This is a derived work from RTKLIB http://www.rtklib.com/ + * The original source code at https://github.com/tomojitakasu/RTKLIB is + * released under the BSD 2-clause license with an additional exclusive clause + * that does not apply here. This additional clause is reproduced below: + * + * " The software package includes some companion executive binaries or shared + * libraries necessary to execute APs on Windows. These licenses succeed to the + * original ones of these software. " + * + * Neither the executive binaries nor the shared libraries are required by, used + * or included in GNSS-SDR. + * + * ----------------------------------------------------------------------------- + * Copyright (C) 2007-2013, T. Takasu + * Copyright (C) 2017-2019, Javier Arribas + * Copyright (C) 2017-2023, Carles Fernandez + * All rights reserved. + * + * SPDX-License-Identifier: BSD-2-Clause + * + * -----------------------------------------------------------------------*/ + +#include "rtklib_solver.h" +#include "Beidou_DNAV.h" +#include "gnss_sdr_filesystem.h" +#include "rtklib_rtkpos.h" +#include "rtklib_solution.h" +#include +#include +#include +#include +#include +#include +#include + + +Rtklib_Solver::Rtklib_Solver(const rtk_t &rtk, + const std::string &dump_filename, + uint32_t type_of_rx, + bool flag_dump_to_file, + bool flag_dump_to_mat, + Pvt_Conf conf) : d_dump_filename(dump_filename), + d_rtk(rtk), + d_conf(std::move(conf)), + d_type_of_rx(type_of_rx), + d_flag_dump_enabled(flag_dump_to_file), + d_flag_dump_mat_enabled(flag_dump_to_mat) +{ + // see freq index at src/algorithms/libs/rtklib/rtklib_rtkcmn.cc + // function: satwavelen + d_rtklib_freq_index[0] = 0; + d_rtklib_freq_index[1] = 1; + d_rtklib_freq_index[2] = 2; + + d_rtklib_band_index["1G"] = 0; + d_rtklib_band_index["1C"] = 0; + d_rtklib_band_index["1B"] = 0; + d_rtklib_band_index["B1"] = 0; + d_rtklib_band_index["B3"] = 2; + d_rtklib_band_index["2G"] = 1; + d_rtklib_band_index["2S"] = 1; + d_rtklib_band_index["7X"] = 2; + d_rtklib_band_index["5X"] = 2; + d_rtklib_band_index["L5"] = 2; + d_rtklib_band_index["E6"] = 0; + + switch (d_type_of_rx) + { + case 6: // E5b only + d_rtklib_freq_index[2] = 4; + break; + case 11: // GPS L1 C/A + Galileo E5b + d_rtklib_freq_index[2] = 4; + break; + case 15: // Galileo E1B + Galileo E5b + d_rtklib_freq_index[2] = 4; + break; + case 18: // GPS L2C + Galileo E5b + d_rtklib_freq_index[2] = 4; + break; + case 19: // Galileo E5a + Galileo E5b + d_rtklib_band_index["5X"] = 0; + d_rtklib_freq_index[0] = 2; + d_rtklib_freq_index[2] = 4; + break; + case 20: // GPS L5 + Galileo E5b + d_rtklib_band_index["L5"] = 0; + d_rtklib_freq_index[0] = 2; + d_rtklib_freq_index[2] = 4; + break; + case 100: // E6B only + d_rtklib_freq_index[0] = 3; + break; + case 101: // E1 + E6B + d_rtklib_band_index["E6"] = 1; + d_rtklib_freq_index[1] = 3; + break; + case 102: // E5a + E6B + d_rtklib_band_index["E6"] = 1; + d_rtklib_freq_index[1] = 3; + break; + case 103: // E5b + E6B + d_rtklib_band_index["E6"] = 1; + d_rtklib_freq_index[1] = 3; + d_rtklib_freq_index[2] = 4; + break; + case 104: // Galileo E1B + Galileo E5a + Galileo E6B + d_rtklib_band_index["E6"] = 1; + d_rtklib_freq_index[1] = 3; + break; + case 105: // Galileo E1B + Galileo E5b + Galileo E6B + d_rtklib_freq_index[2] = 4; + d_rtklib_band_index["E6"] = 1; + d_rtklib_freq_index[1] = 3; + break; + case 106: // GPS L1 C/A + Galileo E1B + Galileo E6B + case 107: // GPS L1 C/A + Galileo E6B + d_rtklib_band_index["E6"] = 1; + d_rtklib_freq_index[1] = 3; + break; + } + // auto empty_map = std::map < int, HAS_obs_corrections >> (); + // d_has_obs_corr_map["L1 C/A"] = empty_map; + + // ############# ENABLE DATA FILE LOG ################# + if (d_flag_dump_enabled == true) + { + if (d_dump_file.is_open() == false) + { + try + { + d_dump_file.exceptions(std::ofstream::failbit | std::ofstream::badbit); + d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary); + LOG(INFO) << "PVT lib dump enabled Log file: " << d_dump_filename.c_str(); + } + catch (const std::ofstream::failure &e) + { + LOG(WARNING) << "Exception opening RTKLIB dump file " << e.what(); + } + } + } +} + + +Rtklib_Solver::~Rtklib_Solver() +{ + DLOG(INFO) << "Rtklib_Solver destructor called."; + if (d_dump_file.is_open() == true) + { + const auto pos = d_dump_file.tellp(); + try + { + d_dump_file.close(); + } + catch (const std::exception &ex) + { + LOG(WARNING) << "Exception in destructor closing the RTKLIB dump file " << ex.what(); + } + if (pos == 0) + { + errorlib::error_code ec; + if (!fs::remove(fs::path(d_dump_filename), ec)) + { + std::cerr << "Problem removing temporary file " << d_dump_filename << '\n'; + } + d_flag_dump_mat_enabled = false; + } + } + if (d_flag_dump_mat_enabled) + { + try + { + save_matfile(); + } + catch (const std::exception &ex) + { + LOG(WARNING) << "Exception in destructor saving the PVT .mat dump file " << ex.what(); + } + } +} + + +bool Rtklib_Solver::save_matfile() const +{ + // READ DUMP FILE + const std::string dump_filename = d_dump_filename; + const int32_t number_of_double_vars = 21; + const int32_t number_of_uint32_vars = 2; + const int32_t number_of_uint8_vars = 3; + const int32_t number_of_float_vars = 2; + const int32_t epoch_size_bytes = sizeof(double) * number_of_double_vars + + sizeof(uint32_t) * number_of_uint32_vars + + sizeof(uint8_t) * number_of_uint8_vars + + sizeof(float) * number_of_float_vars; + std::ifstream dump_file; + dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit); + try + { + dump_file.open(dump_filename.c_str(), std::ios::binary | std::ios::ate); + } + catch (const std::ifstream::failure &e) + { + std::cerr << "Problem opening dump file:" << e.what() << '\n'; + return false; + } + // count number of epochs and rewind + int64_t num_epoch = 0LL; + if (dump_file.is_open()) + { + std::cout << "Generating .mat file for " << dump_filename << '\n'; + const std::ifstream::pos_type size = dump_file.tellg(); + num_epoch = static_cast(size) / static_cast(epoch_size_bytes); + dump_file.seekg(0, std::ios::beg); + } + else + { + return false; + } + + auto TOW_at_current_symbol_ms = std::vector(num_epoch); + auto week = std::vector(num_epoch); + auto RX_time = std::vector(num_epoch); + auto user_clk_offset = std::vector(num_epoch); + auto pos_x = std::vector(num_epoch); + auto pos_y = std::vector(num_epoch); + auto pos_z = std::vector(num_epoch); + auto vel_x = std::vector(num_epoch); + auto vel_y = std::vector(num_epoch); + auto vel_z = std::vector(num_epoch); + auto cov_xx = std::vector(num_epoch); + auto cov_yy = std::vector(num_epoch); + auto cov_zz = std::vector(num_epoch); + auto cov_xy = std::vector(num_epoch); + auto cov_yz = std::vector(num_epoch); + auto cov_zx = std::vector(num_epoch); + auto latitude = std::vector(num_epoch); + auto longitude = std::vector(num_epoch); + auto height = std::vector(num_epoch); + auto valid_sats = std::vector(num_epoch); + auto solution_status = std::vector(num_epoch); + auto solution_type = std::vector(num_epoch); + auto AR_ratio_factor = std::vector(num_epoch); + auto AR_ratio_threshold = std::vector(num_epoch); + auto gdop = std::vector(num_epoch); + auto pdop = std::vector(num_epoch); + auto hdop = std::vector(num_epoch); + auto vdop = std::vector(num_epoch); + + try + { + if (dump_file.is_open()) + { + for (int64_t i = 0; i < num_epoch; i++) + { + dump_file.read(reinterpret_cast(&TOW_at_current_symbol_ms[i]), sizeof(uint32_t)); + dump_file.read(reinterpret_cast(&week[i]), sizeof(uint32_t)); + dump_file.read(reinterpret_cast(&RX_time[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&user_clk_offset[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&pos_x[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&pos_y[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&pos_z[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&vel_x[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&vel_y[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&vel_z[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&cov_xx[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&cov_yy[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&cov_zz[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&cov_xy[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&cov_yz[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&cov_zx[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&latitude[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&longitude[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&height[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&valid_sats[i]), sizeof(uint8_t)); + dump_file.read(reinterpret_cast(&solution_status[i]), sizeof(uint8_t)); + dump_file.read(reinterpret_cast(&solution_type[i]), sizeof(uint8_t)); + dump_file.read(reinterpret_cast(&AR_ratio_factor[i]), sizeof(float)); + dump_file.read(reinterpret_cast(&AR_ratio_threshold[i]), sizeof(float)); + dump_file.read(reinterpret_cast(&gdop[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&pdop[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&hdop[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&vdop[i]), sizeof(double)); + } + } + dump_file.close(); + } + catch (const std::ifstream::failure &e) + { + std::cerr << "Problem reading dump file:" << e.what() << '\n'; + return false; + } + + // WRITE MAT FILE + mat_t *matfp; + matvar_t *matvar; + std::string filename = dump_filename; + filename.erase(filename.length() - 4, 4); + filename.append(".mat"); + matfp = Mat_CreateVer(filename.c_str(), nullptr, MAT_FT_MAT73); + if (reinterpret_cast(matfp) != nullptr) + { + std::array dims{1, static_cast(num_epoch)}; + matvar = Mat_VarCreate("TOW_at_current_symbol_ms", MAT_C_UINT32, MAT_T_UINT32, 2, dims.data(), TOW_at_current_symbol_ms.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("week", MAT_C_UINT32, MAT_T_UINT32, 2, dims.data(), week.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("RX_time", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), RX_time.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("user_clk_offset", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), user_clk_offset.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("pos_x", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), pos_x.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("pos_y", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), pos_y.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("pos_z", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), pos_z.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("vel_x", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), vel_x.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("vel_y", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), vel_y.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("vel_z", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), vel_z.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("cov_xx", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_xx.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("cov_yy", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_yy.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("cov_zz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_zz.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("cov_xy", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_xy.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("cov_yz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_yz.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("cov_zx", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_zx.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("latitude", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), latitude.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("longitude", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), longitude.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("height", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), height.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("valid_sats", MAT_C_UINT8, MAT_T_UINT8, 2, dims.data(), valid_sats.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("solution_status", MAT_C_UINT8, MAT_T_UINT8, 2, dims.data(), solution_status.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("solution_type", MAT_C_UINT8, MAT_T_UINT8, 2, dims.data(), solution_type.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("AR_ratio_factor", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims.data(), AR_ratio_factor.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("AR_ratio_threshold", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims.data(), AR_ratio_threshold.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("gdop", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), gdop.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("pdop", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), pdop.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("hdop", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), hdop.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("vdop", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), vdop.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + } + + Mat_Close(matfp); + return true; +} + + +double Rtklib_Solver::get_gdop() const +{ + return d_dop[0]; +} + + +double Rtklib_Solver::get_pdop() const +{ + return d_dop[1]; +} + + +double Rtklib_Solver::get_hdop() const +{ + return d_dop[2]; +} + + +double Rtklib_Solver::get_vdop() const +{ + return d_dop[3]; +} + + +Monitor_Pvt Rtklib_Solver::get_monitor_pvt() const +{ + return d_monitor_pvt; +} + + +void Rtklib_Solver::store_has_data(const Galileo_HAS_data &new_has_data) +{ + // Compute time of application HAS SIS ICD, Issue 1.0, Section 7.7 + uint16_t toh = new_has_data.header.toh; + uint32_t hr = std::floor(new_has_data.tow / 3600); + uint32_t tmt = 0; + if ((hr * 3600 + toh) <= new_has_data.tow) + { + tmt = hr * 3600 + toh; + } + else + { + tmt = (hr - 1) * 3600 + toh; + } + + const std::string gps_str("GPS"); + const std::string gal_str("Galileo"); + if (new_has_data.header.orbit_correction_flag) + { + LOG(INFO) << "Received HAS orbit corrections"; + // for each satellite in GPS ephemeris + for (const auto &gpseph : gps_ephemeris_map) + { + int prn = gpseph.second.PRN; + int32_t sis_iod = gpseph.second.IODE_SF3; + uint16_t gnss_iod = new_has_data.get_gnss_iod(gps_str, prn); + if (static_cast(gnss_iod) == sis_iod) + { + float radial_m = new_has_data.get_delta_radial_m(gps_str, prn); + if (std::fabs(radial_m + 10.24) < 0.001) // -10.24 means not available + { + radial_m = 0.0; + } + float in_track_m = new_has_data.get_delta_in_track_m(gps_str, prn); + if (std::fabs(in_track_m + 16.384) < 0.001) // -16.384 means not available + { + in_track_m = 0.0; + } + float cross_track_m = new_has_data.get_delta_in_track_m(gps_str, prn); + if (std::fabs(cross_track_m + 16.384) < 0.001) // -16.384 means not available + { + cross_track_m = 0.0; + } + d_has_orbit_corrections_store_map[gps_str][prn].radial_m = radial_m; + d_has_orbit_corrections_store_map[gps_str][prn].in_track_m = in_track_m; + d_has_orbit_corrections_store_map[gps_str][prn].cross_track_m = cross_track_m; + d_has_orbit_corrections_store_map[gps_str][prn].valid_until = tmt + + new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_orbit_corrections); + d_has_orbit_corrections_store_map[gps_str][prn].iod = gnss_iod; + // TODO: check for end of week + } + } + + // for each satellite in Galileo ephemeris + for (const auto &galeph : galileo_ephemeris_map) + { + int prn = galeph.second.PRN; + int32_t sis_iod = galeph.second.IOD_ephemeris; + uint16_t gnss_iod = new_has_data.get_gnss_iod(gal_str, prn); + if (static_cast(gnss_iod) == sis_iod) + { + float radial_m = new_has_data.get_delta_radial_m(gal_str, prn); + if (std::fabs(radial_m + 10.24) < 0.001) // -10.24 means not available + { + radial_m = 0.0; + } + float in_track_m = new_has_data.get_delta_in_track_m(gal_str, prn); + if (std::fabs(in_track_m + 16.384) < 0.001) // -16.384 means not available + { + in_track_m = 0.0; + } + float cross_track_m = new_has_data.get_delta_in_track_m(gal_str, prn); + if (std::fabs(cross_track_m + 16.384) < 0.001) // -16.384 means not available + { + cross_track_m = 0.0; + } + d_has_orbit_corrections_store_map[gal_str][prn].radial_m = radial_m; + d_has_orbit_corrections_store_map[gal_str][prn].in_track_m = in_track_m; + d_has_orbit_corrections_store_map[gal_str][prn].cross_track_m = cross_track_m; + d_has_orbit_corrections_store_map[gal_str][prn].valid_until = tmt + + new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_orbit_corrections); + d_has_orbit_corrections_store_map[gal_str][prn].iod = gnss_iod; + // TODO: check for end of week + } + } + } + if (new_has_data.header.clock_fullset_flag) + { + LOG(INFO) << "Received HAS clock fullset corrections"; + for (const auto &gpseph : gps_ephemeris_map) + { + int prn = gpseph.second.PRN; + int32_t sis_iod = gpseph.second.IODE_SF3; + auto it = d_has_orbit_corrections_store_map[gps_str].find(prn); + if (it != d_has_orbit_corrections_store_map[gps_str].end()) + { + uint16_t gnss_iod = it->second.iod; + if (static_cast(gnss_iod) == sis_iod) + { + float clock_correction_mult_m = new_has_data.get_clock_correction_mult_m(gps_str, prn); + if ((std::fabs(clock_correction_mult_m + 10.24) < 0.001) || + (std::fabs(clock_correction_mult_m + 20.48) < 0.001) || + (std::fabs(clock_correction_mult_m + 30.72) < 0.001) || + (std::fabs(clock_correction_mult_m + 40.96) < 0.001)) + { + clock_correction_mult_m = 0.0; + } + if ((std::fabs(clock_correction_mult_m - 10.2375) < 0.001) || + (std::fabs(clock_correction_mult_m - 20.475) < 0.001) || + (std::fabs(clock_correction_mult_m - 30.7125) < 0.001) || + (std::fabs(clock_correction_mult_m - 40.95) < 0.001)) + { + // Satellite should not be used! + clock_correction_mult_m = 0.0; + } + d_has_clock_corrections_store_map[gps_str][prn].clock_correction_m = clock_correction_mult_m; + d_has_clock_corrections_store_map[gps_str][prn].valid_until = tmt + + new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_clock_fullset_corrections); + // TODO: check for end of week + } + } + } + + // for each satellite in Galileo ephemeris + for (const auto &galeph : galileo_ephemeris_map) + { + int prn = galeph.second.PRN; + int32_t iod_sis = galeph.second.IOD_ephemeris; + auto it = d_has_orbit_corrections_store_map[gal_str].find(prn); + if (it != d_has_orbit_corrections_store_map[gal_str].end()) + { + uint16_t gnss_iod = it->second.iod; + if (static_cast(gnss_iod) == iod_sis) + { + float clock_correction_mult_m = new_has_data.get_clock_correction_mult_m(gal_str, prn); + // std::cout << "Galileo Satellite " << prn + // << " clock correction=" << new_has_data.get_clock_correction_mult_m(gal_str, prn) + // << std::endl; + if ((std::fabs(clock_correction_mult_m + 10.24) < 0.001) || + (std::fabs(clock_correction_mult_m + 20.48) < 0.001) || + (std::fabs(clock_correction_mult_m + 30.72) < 0.001) || + (std::fabs(clock_correction_mult_m + 40.96) < 0.001)) + { + clock_correction_mult_m = 0.0; + } + d_has_clock_corrections_store_map[gal_str][prn].clock_correction_m = clock_correction_mult_m; + d_has_clock_corrections_store_map[gal_str][prn].valid_until = tmt + + new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_clock_fullset_corrections); + // TODO: check for end of week + } + } + } + } + if (new_has_data.header.clock_subset_flag) + { + LOG(INFO) << "Received HAS clock subset corrections"; + for (const auto &gpseph : gps_ephemeris_map) + { + int prn = gpseph.second.PRN; + int32_t sis_iod = gpseph.second.IODE_SF3; + int32_t gnss_iod = d_has_orbit_corrections_store_map[gps_str][prn].iod; + if (gnss_iod == sis_iod) + { + // d_has_clock_corrections_store_map[gps_str][prn].clock_correction_m = new_has_data.get_clock_subset_correction_mult_m(gps_str, prn); + // d_has_clock_corrections_store_map[gps_str][prn].valid_until = tmt + new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_clock_subset_corrections); + // TODO: check for end of week + } + } + } + if (new_has_data.header.code_bias_flag) + { + LOG(INFO) << "Received HAS code bias corrections"; + uint32_t valid_until = tmt + + new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_code_bias_corrections); + auto signals_gal = new_has_data.get_signals_in_mask(gal_str); + for (const auto &it : signals_gal) + { + auto prns = new_has_data.get_PRNs_in_mask(gal_str); + for (auto prn : prns) + { + float code_bias_m = new_has_data.get_code_bias_m(it, prn); + if ((std::fabs(code_bias_m + 20.48) < 0.01)) // -20.48 means not available + { + code_bias_m = 0.0; + } + d_has_code_bias_store_map[it][prn] = {code_bias_m, valid_until}; + } + } + auto signals_gps = new_has_data.get_signals_in_mask(gps_str); + for (const auto &it : signals_gps) + { + auto prns = new_has_data.get_PRNs_in_mask(gps_str); + for (auto prn : prns) + { + float code_bias_m = new_has_data.get_code_bias_m(it, prn); + if ((std::fabs(code_bias_m + 20.48) < 0.01)) // -20.48 means not available + { + code_bias_m = 0.0; + } + d_has_code_bias_store_map[it][prn] = {code_bias_m, valid_until}; + } + } + } + if (new_has_data.header.phase_bias_flag) + { + LOG(INFO) << "Received HAS phase bias corrections"; + uint32_t valid_until = tmt + + new_has_data.get_validity_interval_s(new_has_data.validity_interval_index_phase_bias_corrections); + + auto signals_gal = new_has_data.get_signals_in_mask(gal_str); + for (const auto &it : signals_gal) + { + auto prns = new_has_data.get_PRNs_in_mask(gal_str); + for (auto prn : prns) + { + float phase_bias_correction_cycles = new_has_data.get_phase_bias_cycle(it, prn); + if (std::fabs(phase_bias_correction_cycles + 10.24) < 0.001) // -10.24 means not available + { + phase_bias_correction_cycles = 0.0; + } + d_has_phase_bias_store_map[it][prn] = {phase_bias_correction_cycles, valid_until}; + // TODO: process Phase Discontinuity Indicator + } + } + auto signals_gps = new_has_data.get_signals_in_mask(gps_str); + for (const auto &it : signals_gps) + { + auto prns = new_has_data.get_PRNs_in_mask(gps_str); + for (auto prn : prns) + { + float phase_bias_correction_cycles = new_has_data.get_phase_bias_cycle(it, prn); + if (std::fabs(phase_bias_correction_cycles + 10.24) < 0.001) // -10.24 means not available + { + phase_bias_correction_cycles = 0.0; + } + d_has_phase_bias_store_map[it][prn] = {phase_bias_correction_cycles, valid_until}; + // TODO: process Phase Discontinuity Indicator + } + } + } +} + + +void Rtklib_Solver::update_has_corrections(const std::map &obs_map) +{ + this->check_has_orbit_clock_validity(obs_map); + this->get_has_biases(obs_map); +} + + +void Rtklib_Solver::check_has_orbit_clock_validity(const std::map &obs_map) +{ + for (const auto &it : obs_map) + { + uint32_t obs_tow = it.second.interp_TOW_ms / 1000.0; + auto prn = static_cast(it.second.PRN); + + if (it.second.System == 'G') + { + auto it_sys = d_has_orbit_corrections_store_map.find("GPS"); + if (it_sys != d_has_orbit_corrections_store_map.end()) + { + auto it_map_corr = it_sys->second.find(prn); + if (it_map_corr != it_sys->second.end()) + { + auto has_data_valid_until = it_map_corr->second.valid_until; + if (has_data_valid_until < obs_tow) + { + // Delete outdated data + it_sys->second.erase(prn); + } + } + } + auto it_sys_clock = d_has_clock_corrections_store_map.find("GPS"); + if (it_sys_clock != d_has_clock_corrections_store_map.end()) + { + auto it_map_corr = it_sys_clock->second.find(prn); + if (it_map_corr != it_sys_clock->second.end()) + { + auto has_data_valid_until = it_map_corr->second.valid_until; + if (has_data_valid_until < obs_tow) + { + // Delete outdated data + it_sys_clock->second.erase(prn); + } + } + } + } + if (it.second.System == 'E') + { + auto it_sys = d_has_orbit_corrections_store_map.find("Galileo"); + if (it_sys != d_has_orbit_corrections_store_map.end()) + { + auto it_map_corr = it_sys->second.find(prn); + if (it_map_corr != it_sys->second.end()) + { + auto has_data_valid_until = it_map_corr->second.valid_until; + if (has_data_valid_until < obs_tow) + { + // Delete outdated data + it_sys->second.erase(prn); + } + } + } + auto it_sys_clock = d_has_clock_corrections_store_map.find("Galileo"); + if (it_sys_clock != d_has_clock_corrections_store_map.end()) + { + auto it_map_corr = it_sys_clock->second.find(prn); + if (it_map_corr != it_sys_clock->second.end()) + { + auto has_data_valid_until = it_map_corr->second.valid_until; + if (has_data_valid_until < obs_tow) + { + // Delete outdated data + it_sys_clock->second.erase(prn); + } + } + } + } + } +} + + +void Rtklib_Solver::get_has_biases(const std::map &obs_map) +{ + d_has_obs_corr_map.clear(); + if (!d_has_clock_corrections_store_map.empty() && !d_has_orbit_corrections_store_map.empty()) + { + const std::vector e1b_signals = {"E1-B I/NAV OS", "E1-C", "E1-B + E1-C"}; + const std::vector e6_signals = {"E6-B C/NAV HAS", "E6-C", "E6-B + E6-C"}; + const std::vector e5_signals = {"E5a-I F/NAV OS", "E5a-Q", "E5a-I+E5a-Q"}; + const std::vector e7_signals = {"E5bI I/NAV OS", "E5b-Q", "E5b-I+E5b-Q"}; + const std::vector g1c_signals = {"L1 C/A"}; + const std::vector g2s_signals = {"L2 CM", "L2 CL", "L2 CM+CL", "L2 P"}; + const std::vector g5_signals = {"L5 I", "L5 Q", "L5 I + L5 Q"}; + + for (const auto &it : obs_map) + { + uint32_t obs_tow = it.second.interp_TOW_ms / 1000.0; + int prn = static_cast(it.second.PRN); + std::string sig(it.second.Signal, 2); + if (it.second.System == 'E') + { + auto it_sys_clock = d_has_clock_corrections_store_map.find("Galileo"); + if (it_sys_clock != d_has_clock_corrections_store_map.end()) + { + auto it_map_corr = it_sys_clock->second.find(prn); + if (it_map_corr != it_sys_clock->second.end()) + { + if (sig == "1B") + { + for (const auto &has_signal : e1b_signals) + { + this->get_current_has_obs_correction(has_signal, obs_tow, prn); + } + } + else if (sig == "E6") + { + for (const auto &has_signal : e6_signals) + { + this->get_current_has_obs_correction(has_signal, obs_tow, prn); + } + } + else if (sig == "5X") + { + for (const auto &has_signal : e5_signals) + { + this->get_current_has_obs_correction(has_signal, obs_tow, prn); + } + } + else if (sig == "7X") + { + for (const auto &has_signal : e7_signals) + { + this->get_current_has_obs_correction(has_signal, obs_tow, prn); + } + } + } + } + } + if (it.second.System == 'G') + { + auto it_sys_clock = d_has_clock_corrections_store_map.find("GPS"); + if (it_sys_clock != d_has_clock_corrections_store_map.end()) + { + auto it_map_corr = it_sys_clock->second.find(prn); + if (it_map_corr != it_sys_clock->second.end()) + { + if (sig == "1C") + { + for (const auto &has_signal : g1c_signals) + { + this->get_current_has_obs_correction(has_signal, obs_tow, prn); + } + } + else if (sig == "2S") + { + for (const auto &has_signal : g2s_signals) + { + this->get_current_has_obs_correction(has_signal, obs_tow, prn); + } + } + else if (sig == "L5") + { + for (const auto &has_signal : g5_signals) + { + this->get_current_has_obs_correction(has_signal, obs_tow, prn); + } + } + } + } + } + } + } +} + + +void Rtklib_Solver::get_current_has_obs_correction(const std::string &signal, uint32_t tow_obs, int prn) +{ + auto code_bias_pair_it = this->d_has_code_bias_store_map[signal].find(prn); + if (code_bias_pair_it != this->d_has_code_bias_store_map[signal].end()) + { + uint32_t valid_until = code_bias_pair_it->second.second; + if (valid_until > tow_obs) + { + this->d_has_obs_corr_map[signal][prn].code_bias_m = code_bias_pair_it->second.first; + } + } + auto phase_bias_pair_it = this->d_has_phase_bias_store_map[signal].find(prn); + if (phase_bias_pair_it != this->d_has_phase_bias_store_map[signal].end()) + { + uint32_t valid_until = phase_bias_pair_it->second.second; + if (valid_until > tow_obs) + { + this->d_has_obs_corr_map[signal][prn].phase_bias_cycle = phase_bias_pair_it->second.first; + } + } +} + + +bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_map, double kf_update_interval_s) +{ + std::map::const_iterator gnss_observables_iter; + std::map::const_iterator galileo_ephemeris_iter; + std::map::const_iterator gps_ephemeris_iter; + std::map::const_iterator gps_cnav_ephemeris_iter; + std::map::const_iterator glonass_gnav_ephemeris_iter; + std::map::const_iterator beidou_ephemeris_iter; + + const Glonass_Gnav_Utc_Model &gnav_utc = this->glonass_gnav_utc_model; + + // ******************************************************************************** + // ****** PREPARE THE DATA (SV EPHEMERIS AND OBSERVATIONS) ************************ + // ******************************************************************************** + int valid_obs = 0; // valid observations counter + int glo_valid_obs = 0; // GLONASS L1/L2 valid observations counter + + d_obs_data.fill({}); + std::vector eph_data(MAXOBS); + std::vector geph_data(MAXOBS); + + // Workaround for NAV/CNAV clash problem + bool gps_dual_band = false; + bool band1 = false; + bool band2 = false; + + for (gnss_observables_iter = gnss_observables_map.cbegin(); + gnss_observables_iter != gnss_observables_map.cend(); + ++gnss_observables_iter) + { + switch (gnss_observables_iter->second.System) + { + case 'G': + { + const std::string sig_(gnss_observables_iter->second.Signal, 2); + if (sig_ == "1C") + { + band1 = true; + } + if (sig_ == "2S") + { + band2 = true; + } + } + break; + default: + { + } + } + } + if (band1 == true and band2 == true) + { + gps_dual_band = true; + } + + for (gnss_observables_iter = gnss_observables_map.cbegin(); + gnss_observables_iter != gnss_observables_map.cend(); + ++gnss_observables_iter) // CHECK INCONSISTENCY when combining GLONASS + other system + { + switch (gnss_observables_iter->second.System) + { + case 'E': + { + const std::string gal_str("Galileo"); + const std::string sig_(gnss_observables_iter->second.Signal, 2); + // Galileo E1 + if (sig_ == "1B") + { + // 1 Gal - find the ephemeris for the current GALILEO SV observation. The SV PRN ID is the map key + galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (galileo_ephemeris_iter != galileo_ephemeris_map.cend()) + { + // convert ephemeris from GNSS-SDR class to RTKLIB structure + eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second, + this->d_has_orbit_corrections_store_map[gal_str], + this->d_has_clock_corrections_store_map[gal_str]); + // convert observation from GNSS-SDR class to RTKLIB structure + obsd_t newobs{}; + d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, + gnss_observables_iter->second, + d_has_obs_corr_map, + galileo_ephemeris_iter->second.WN, + d_rtklib_band_index[sig_]); + valid_obs++; + } + else // the ephemeris are not available for this SV + { + DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; + } + } + + // Galileo E5 + if ((sig_ == "5X") || (sig_ == "7X")) + { + // 1 Gal - find the ephemeris for the current GALILEO SV observation. The SV PRN ID is the map key + galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (galileo_ephemeris_iter != galileo_ephemeris_map.cend()) + { + bool found_E1_obs = false; + for (int i = 0; i < valid_obs; i++) + { + if (eph_data[i].sat == (static_cast(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO))) + { + d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs], + gnss_observables_iter->second, + d_has_obs_corr_map, + galileo_ephemeris_iter->second.WN, + d_rtklib_band_index[sig_]); + found_E1_obs = true; + break; + } + } + if (!found_E1_obs) + { + // insert Galileo E5 obs as new obs and also insert its ephemeris + // convert ephemeris from GNSS-SDR class to RTKLIB structure + eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second, + this->d_has_orbit_corrections_store_map[gal_str], + this->d_has_clock_corrections_store_map[gal_str]); + // convert observation from GNSS-SDR class to RTKLIB structure + const auto default_code_ = static_cast(CODE_NONE); + obsd_t newobs = {{0, 0}, '0', '0', {}, {}, + {default_code_, default_code_, default_code_}, + {}, {0.0, 0.0, 0.0}, {}}; + d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, + gnss_observables_iter->second, + d_has_obs_corr_map, + galileo_ephemeris_iter->second.WN, + d_rtklib_band_index[sig_]); + valid_obs++; + } + } + else // the ephemeris are not available for this SV + { + DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; + } + } + if (sig_ == "E6" && d_conf.use_e6_for_pvt) + { + galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (galileo_ephemeris_iter != galileo_ephemeris_map.cend()) + { + bool found_E1_obs = false; + for (int i = 0; i < valid_obs; i++) + { + if (eph_data[i].sat == (static_cast(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO))) + { + d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs], + gnss_observables_iter->second, + d_has_obs_corr_map, + galileo_ephemeris_iter->second.WN, + d_rtklib_band_index[sig_]); + found_E1_obs = true; + break; + } + } + if (!found_E1_obs) + { + // insert Galileo E6 obs as new obs and also insert its ephemeris + // convert ephemeris from GNSS-SDR class to RTKLIB structure + eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second, + this->d_has_orbit_corrections_store_map[gal_str], + this->d_has_clock_corrections_store_map[gal_str]); + // convert observation from GNSS-SDR class to RTKLIB structure + const auto default_code_ = static_cast(CODE_NONE); + obsd_t newobs = {{0, 0}, '0', '0', {}, {}, + {default_code_, default_code_, default_code_}, + {}, {0.0, 0.0, 0.0}, {}}; + d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, + gnss_observables_iter->second, + d_has_obs_corr_map, + galileo_ephemeris_iter->second.WN, + d_rtklib_band_index[sig_]); + valid_obs++; + } + } + else // the ephemeris are not available for this SV + { + DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; + } + } + if (sig_ == "E6") + { + galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (galileo_ephemeris_iter != galileo_ephemeris_map.cend()) + { + bool found_E1_obs = false; + for (int i = 0; i < valid_obs; i++) + { + if (eph_data[i].sat == (static_cast(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO))) + { + d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs], + gnss_observables_iter->second, + galileo_ephemeris_iter->second.WN, + 2); // Band E6 + found_E1_obs = true; + break; + } + } + if (!found_E1_obs) + { + // insert Galileo E6 obs as new obs and also insert its ephemeris + // convert ephemeris from GNSS-SDR class to RTKLIB structure + eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second); + // convert observation from GNSS-SDR class to RTKLIB structure + const auto default_code_ = static_cast(CODE_NONE); + obsd_t newobs = {{0, 0}, '0', '0', {}, {}, + {default_code_, default_code_, default_code_}, + {}, {0.0, 0.0, 0.0}, {}}; + d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, + gnss_observables_iter->second, + galileo_ephemeris_iter->second.WN, + 2); // Band E6 + // std::cout << "Week " << galileo_ephemeris_iter->second.WN << '\n'; + valid_obs++; + } + } + else // the ephemeris are not available for this SV + { + DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; + } + } + break; + } + case 'G': + { + // GPS L1 + // 1 GPS - find the ephemeris for the current GPS SV observation. The SV PRN ID is the map key + const std::string gps_str("GPS"); + const std::string sig_(gnss_observables_iter->second.Signal, 2); + if (sig_ == "1C") + { + gps_ephemeris_iter = gps_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (gps_ephemeris_iter != gps_ephemeris_map.cend()) + { + // convert ephemeris from GNSS-SDR class to RTKLIB structure + eph_data[valid_obs] = eph_to_rtklib(gps_ephemeris_iter->second, + this->d_has_orbit_corrections_store_map[gps_str], + this->d_has_clock_corrections_store_map[gps_str], + this->is_pre_2009()); + // convert observation from GNSS-SDR class to RTKLIB structure + obsd_t newobs{}; + d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, + gnss_observables_iter->second, + d_has_obs_corr_map, + gps_ephemeris_iter->second.WN, + d_rtklib_band_index[sig_], + this->is_pre_2009()); + valid_obs++; + } + else // the ephemeris are not available for this SV + { + DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->first; + } + } + // GPS L2 (todo: solve NAV/CNAV clash) + if ((sig_ == "2S") and (gps_dual_band == false)) + { + gps_cnav_ephemeris_iter = gps_cnav_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (gps_cnav_ephemeris_iter != gps_cnav_ephemeris_map.cend()) + { + // 1. Find the same satellite in GPS L1 band + gps_ephemeris_iter = gps_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (gps_ephemeris_iter != gps_ephemeris_map.cend()) + { + /* By the moment, GPS L2 observables are not used in pseudorange computations if GPS L1 is available + // 2. If found, replace the existing GPS L1 ephemeris with the GPS L2 ephemeris + // (more precise!), and attach the L2 observation to the L1 observation in RTKLIB structure + for (int i = 0; i < valid_obs; i++) + { + if (eph_data[i].sat == static_cast(gnss_observables_iter->second.PRN)) + { + eph_data[i] = eph_to_rtklib(gps_cnav_ephemeris_iter->second); + d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs], + gnss_observables_iter->second, + eph_data[i].week, + d_rtklib_band_index[sig_]); + break; + } + } + */ + } + else + { + // 3. If not found, insert the GPS L2 ephemeris and the observation + // convert ephemeris from GNSS-SDR class to RTKLIB structure + eph_data[valid_obs] = eph_to_rtklib(gps_cnav_ephemeris_iter->second); + // convert observation from GNSS-SDR class to RTKLIB structure + const auto default_code_ = static_cast(CODE_NONE); + obsd_t newobs = {{0, 0}, '0', '0', {}, {}, + {default_code_, default_code_, default_code_}, + {}, {0.0, 0.0, 0.0}, {}}; + d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, + gnss_observables_iter->second, + gps_cnav_ephemeris_iter->second.WN, + d_rtklib_band_index[sig_]); + valid_obs++; + } + } + else // the ephemeris are not available for this SV + { + DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; + } + } + // GPS L5 + if (sig_ == "L5") + { + gps_cnav_ephemeris_iter = gps_cnav_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (gps_cnav_ephemeris_iter != gps_cnav_ephemeris_map.cend()) + { + // 1. Find the same satellite in GPS L1 band + gps_ephemeris_iter = gps_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (gps_ephemeris_iter != gps_ephemeris_map.cend()) + { + // 2. If found, replace the existing GPS L1 ephemeris with the GPS L5 ephemeris + // (more precise!), and attach the L5 observation to the L1 observation in RTKLIB structure + for (int i = 0; i < valid_obs; i++) + { + if (eph_data[i].sat == static_cast(gnss_observables_iter->second.PRN)) + { + eph_data[i] = eph_to_rtklib(gps_cnav_ephemeris_iter->second); + d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i], + gnss_observables_iter->second, + gps_cnav_ephemeris_iter->second.WN, + d_rtklib_band_index[sig_]); + break; + } + } + } + else + { + // 3. If not found, insert the GPS L5 ephemeris and the observation + // convert ephemeris from GNSS-SDR class to RTKLIB structure + eph_data[valid_obs] = eph_to_rtklib(gps_cnav_ephemeris_iter->second); + // convert observation from GNSS-SDR class to RTKLIB structure + const auto default_code_ = static_cast(CODE_NONE); + obsd_t newobs = {{0, 0}, '0', '0', {}, {}, + {default_code_, default_code_, default_code_}, + {}, {0.0, 0.0, 0.0}, {}}; + d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, + gnss_observables_iter->second, + d_has_obs_corr_map, + gps_cnav_ephemeris_iter->second.WN, + d_rtklib_band_index[sig_]); + valid_obs++; + } + } + else // the ephemeris are not available for this SV + { + DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; + } + } + break; + } + case 'R': // TODO This should be using rtk lib nomenclature + { + const std::string sig_(gnss_observables_iter->second.Signal); + // GLONASS GNAV L1 + if (sig_ == "1G") + { + // 1 Glo - find the ephemeris for the current GLONASS SV observation. The SV Slot Number (PRN ID) is the map key + glonass_gnav_ephemeris_iter = glonass_gnav_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (glonass_gnav_ephemeris_iter != glonass_gnav_ephemeris_map.cend()) + { + // convert ephemeris from GNSS-SDR class to RTKLIB structure + geph_data[glo_valid_obs] = eph_to_rtklib(glonass_gnav_ephemeris_iter->second, gnav_utc); + // convert observation from GNSS-SDR class to RTKLIB structure + obsd_t newobs{}; + d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, + gnss_observables_iter->second, + glonass_gnav_ephemeris_iter->second.d_WN, + d_rtklib_band_index[sig_]); + glo_valid_obs++; + } + else // the ephemeris are not available for this SV + { + DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; + } + } + // GLONASS GNAV L2 + if (sig_ == "2G") + { + // 1 GLONASS - find the ephemeris for the current GLONASS SV observation. The SV PRN ID is the map key + glonass_gnav_ephemeris_iter = glonass_gnav_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (glonass_gnav_ephemeris_iter != glonass_gnav_ephemeris_map.cend()) + { + bool found_L1_obs = false; + for (int i = 0; i < glo_valid_obs; i++) + { + if (geph_data[i].sat == (static_cast(gnss_observables_iter->second.PRN + NSATGPS))) + { + d_obs_data[i + valid_obs] = insert_obs_to_rtklib(d_obs_data[i + valid_obs], + gnss_observables_iter->second, + glonass_gnav_ephemeris_iter->second.d_WN, + d_rtklib_band_index[sig_]); + found_L1_obs = true; + break; + } + } + if (!found_L1_obs) + { + // insert GLONASS GNAV L2 obs as new obs and also insert its ephemeris + // convert ephemeris from GNSS-SDR class to RTKLIB structure + geph_data[glo_valid_obs] = eph_to_rtklib(glonass_gnav_ephemeris_iter->second, gnav_utc); + // convert observation from GNSS-SDR class to RTKLIB structure + obsd_t newobs{}; + d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, + gnss_observables_iter->second, + glonass_gnav_ephemeris_iter->second.d_WN, + d_rtklib_band_index[sig_]); + glo_valid_obs++; + } + } + else // the ephemeris are not available for this SV + { + DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; + } + } + break; + } + case 'C': + { + // BEIDOU B1I + // - find the ephemeris for the current BEIDOU SV observation. The SV PRN ID is the map key + const std::string sig_(gnss_observables_iter->second.Signal); + if (sig_ == "B1") + { + beidou_ephemeris_iter = beidou_dnav_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (beidou_ephemeris_iter != beidou_dnav_ephemeris_map.cend()) + { + // convert ephemeris from GNSS-SDR class to RTKLIB structure + eph_data[valid_obs] = eph_to_rtklib(beidou_ephemeris_iter->second); + // convert observation from GNSS-SDR class to RTKLIB structure + obsd_t newobs{}; + d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, + gnss_observables_iter->second, + beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET, + d_rtklib_band_index[sig_]); + valid_obs++; + } + else // the ephemeris are not available for this SV + { + DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->first; + } + } + // BeiDou B3 + if (sig_ == "B3") + { + beidou_ephemeris_iter = beidou_dnav_ephemeris_map.find(gnss_observables_iter->second.PRN); + if (beidou_ephemeris_iter != beidou_dnav_ephemeris_map.cend()) + { + bool found_B1I_obs = false; + for (int i = 0; i < valid_obs; i++) + { + if (eph_data[i].sat == (static_cast(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO + NSATGAL + NSATQZS))) + { + d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs], + gnss_observables_iter->second, + beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET, + d_rtklib_band_index[sig_]); + found_B1I_obs = true; + break; + } + } + if (!found_B1I_obs) + { + // insert BeiDou B3I obs as new obs and also insert its ephemeris + // convert ephemeris from GNSS-SDR class to RTKLIB structure + eph_data[valid_obs] = eph_to_rtklib(beidou_ephemeris_iter->second); + // convert observation from GNSS-SDR class to RTKLIB structure + const auto default_code_ = static_cast(CODE_NONE); + obsd_t newobs = {{0, 0}, '0', '0', {}, {}, + {default_code_, default_code_, default_code_}, + {}, {0.0, 0.0, 0.0}, {}}; + d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, + gnss_observables_iter->second, + beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET, + d_rtklib_band_index[sig_]); + valid_obs++; + } + } + else // the ephemeris are not available for this SV + { + DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; + } + } + break; + } + + default: + DLOG(INFO) << "Hybrid observables: Unknown GNSS"; + break; + } + } + + // ********************************************************************** + // ****** SOLVE PVT****************************************************** + // ********************************************************************** + + this->set_valid_position(false); + if ((valid_obs + glo_valid_obs) > 3) + { + int result = 0; + d_nav_data = {}; + d_nav_data.eph = eph_data.data(); + d_nav_data.geph = geph_data.data(); + d_nav_data.n = valid_obs; + d_nav_data.ng = glo_valid_obs; + if (gps_iono.valid) + { + d_nav_data.ion_gps[0] = gps_iono.alpha0; + d_nav_data.ion_gps[1] = gps_iono.alpha1; + d_nav_data.ion_gps[2] = gps_iono.alpha2; + d_nav_data.ion_gps[3] = gps_iono.alpha3; + d_nav_data.ion_gps[4] = gps_iono.beta0; + d_nav_data.ion_gps[5] = gps_iono.beta1; + d_nav_data.ion_gps[6] = gps_iono.beta2; + d_nav_data.ion_gps[7] = gps_iono.beta3; + } + if (!(gps_iono.valid) and gps_cnav_iono.valid) + { + d_nav_data.ion_gps[0] = gps_cnav_iono.alpha0; + d_nav_data.ion_gps[1] = gps_cnav_iono.alpha1; + d_nav_data.ion_gps[2] = gps_cnav_iono.alpha2; + d_nav_data.ion_gps[3] = gps_cnav_iono.alpha3; + d_nav_data.ion_gps[4] = gps_cnav_iono.beta0; + d_nav_data.ion_gps[5] = gps_cnav_iono.beta1; + d_nav_data.ion_gps[6] = gps_cnav_iono.beta2; + d_nav_data.ion_gps[7] = gps_cnav_iono.beta3; + } + if (galileo_iono.ai0 != 0.0) + { + d_nav_data.ion_gal[0] = galileo_iono.ai0; + d_nav_data.ion_gal[1] = galileo_iono.ai1; + d_nav_data.ion_gal[2] = galileo_iono.ai2; + d_nav_data.ion_gal[3] = 0.0; + } + if (beidou_dnav_iono.valid) + { + d_nav_data.ion_cmp[0] = beidou_dnav_iono.alpha0; + d_nav_data.ion_cmp[1] = beidou_dnav_iono.alpha1; + d_nav_data.ion_cmp[2] = beidou_dnav_iono.alpha2; + d_nav_data.ion_cmp[3] = beidou_dnav_iono.alpha3; + d_nav_data.ion_cmp[4] = beidou_dnav_iono.beta0; + d_nav_data.ion_cmp[5] = beidou_dnav_iono.beta0; + d_nav_data.ion_cmp[6] = beidou_dnav_iono.beta0; + d_nav_data.ion_cmp[7] = beidou_dnav_iono.beta3; + } + if (gps_utc_model.valid) + { + d_nav_data.utc_gps[0] = gps_utc_model.A0; + d_nav_data.utc_gps[1] = gps_utc_model.A1; + d_nav_data.utc_gps[2] = gps_utc_model.tot; + d_nav_data.utc_gps[3] = gps_utc_model.WN_T; + d_nav_data.leaps = gps_utc_model.DeltaT_LS; + } + if (!(gps_utc_model.valid) and gps_cnav_utc_model.valid) + { + d_nav_data.utc_gps[0] = gps_cnav_utc_model.A0; + d_nav_data.utc_gps[1] = gps_cnav_utc_model.A1; + d_nav_data.utc_gps[2] = gps_cnav_utc_model.tot; + d_nav_data.utc_gps[3] = gps_cnav_utc_model.WN_T; + d_nav_data.leaps = gps_cnav_utc_model.DeltaT_LS; + } + if (glonass_gnav_utc_model.valid) + { + d_nav_data.utc_glo[0] = glonass_gnav_utc_model.d_tau_c; // ?? + d_nav_data.utc_glo[1] = 0.0; // ?? + d_nav_data.utc_glo[2] = 0.0; // ?? + d_nav_data.utc_glo[3] = 0.0; // ?? + } + if (galileo_utc_model.A0 != 0.0) + { + d_nav_data.utc_gal[0] = galileo_utc_model.A0; + d_nav_data.utc_gal[1] = galileo_utc_model.A1; + d_nav_data.utc_gal[2] = galileo_utc_model.tot; + d_nav_data.utc_gal[3] = galileo_utc_model.WNot; + d_nav_data.leaps = galileo_utc_model.Delta_tLS; + } + if (beidou_dnav_utc_model.valid) + { + d_nav_data.utc_cmp[0] = beidou_dnav_utc_model.A0_UTC; + d_nav_data.utc_cmp[1] = beidou_dnav_utc_model.A1_UTC; + d_nav_data.utc_cmp[2] = 0.0; // ?? + d_nav_data.utc_cmp[3] = 0.0; // ?? + d_nav_data.leaps = beidou_dnav_utc_model.DeltaT_LS; + } + + /* update carrier wave length using native function call in RTKlib */ + for (int i = 0; i < MAXSAT; i++) + { + for (int j = 0; j < NFREQ; j++) + { + d_nav_data.lam[i][j] = satwavelen(i + 1, d_rtklib_freq_index[j], &d_nav_data); + } + } + + result = rtkpos(&d_rtk, d_obs_data.data(), valid_obs + glo_valid_obs, &d_nav_data); + + if (result == 0) + { + LOG(INFO) << "RTKLIB rtkpos error: " << d_rtk.errbuf; + d_rtk.neb = 0; // clear error buffer to avoid repeating the error message + this->set_time_offset_s(0.0); // reset rx time estimation + this->set_num_valid_observations(0); + if (d_conf.enable_pvt_kf == true) + { + d_pvt_kf.reset_Kf(); + } + } + else + { + this->set_num_valid_observations(d_rtk.sol.ns); // record the number of valid satellites used by the PVT solver + pvt_sol = d_rtk.sol; + // DOP computation + unsigned int used_sats = 0; + for (unsigned int i = 0; i < MAXSAT; i++) + { + pvt_ssat[i] = d_rtk.ssat[i]; + if (d_rtk.ssat[i].vs == 1) + { + used_sats++; + } + } + + std::vector azel(used_sats * 2); + int index_aux = 0; + for (auto &i : d_rtk.ssat) + { + if (i.vs == 1) + { + azel[2 * index_aux] = i.azel[0]; + azel[2 * index_aux + 1] = i.azel[1]; + index_aux++; + } + } + + if (index_aux > 0) + { + dops(index_aux, azel.data(), 0.0, d_dop.data()); + } + this->set_valid_position(true); + std::array rx_position_and_time{}; + + if (d_conf.enable_pvt_kf == true) + { + if (d_pvt_kf.is_initialized() == false) + { + arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; + arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; + arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], + pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; + + d_pvt_kf.init_Kf(p, + v, + res_p, + kf_update_interval_s, + d_conf.estatic_measures_sd, + d_conf.measures_ecef_pos_sd_m, + d_conf.measures_ecef_vel_sd_ms, + d_conf.system_ecef_pos_sd_m, + d_conf.system_ecef_vel_sd_ms); + } + else + { + arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; + arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; + arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], + pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; + + d_pvt_kf.run_Kf(p, v, res_p); + d_pvt_kf.get_pv_Kf(p, v); + pvt_sol.rr[0] = p[0]; // [m] + pvt_sol.rr[1] = p[1]; // [m] + pvt_sol.rr[2] = p[2]; // [m] + pvt_sol.rr[3] = v[0]; // [ms] + pvt_sol.rr[4] = v[1]; // [ms] + pvt_sol.rr[5] = v[2]; // [ms] + } + } + + rx_position_and_time[0] = pvt_sol.rr[0]; // [m] + rx_position_and_time[1] = pvt_sol.rr[1]; // [m] + rx_position_and_time[2] = pvt_sol.rr[2]; // [m] + + // todo: fix this ambiguity in the RTKLIB units in receiver clock offset! + if (d_rtk.opt.mode == PMODE_SINGLE) + { + // if the RTKLIB solver is set to SINGLE, the dtr is already expressed in [s] + // add also the clock offset from gps to galileo (pvt_sol.dtr[2]) + rx_position_and_time[3] = pvt_sol.dtr[0] + pvt_sol.dtr[2]; + } + else + { + // the receiver clock offset is expressed in [meters], so we convert it into [s] + // add also the clock offset from gps to galileo (pvt_sol.dtr[2]) + rx_position_and_time[3] = pvt_sol.dtr[2] + pvt_sol.dtr[0] / SPEED_OF_LIGHT_M_S; + } + this->set_rx_pos({rx_position_and_time[0], rx_position_and_time[1], rx_position_and_time[2]}); // save ECEF position for the next iteration + + // compute Ground speed and COG + double ground_speed_ms = 0.0; + std::array pos{}; + std::array enuv{}; + ecef2pos(pvt_sol.rr, pos.data()); + ecef2enu(pos.data(), &pvt_sol.rr[3], enuv.data()); + this->set_speed_over_ground(norm_rtk(enuv.data(), 2)); + double new_cog; + if (ground_speed_ms >= 1.0) + { + new_cog = atan2(enuv[0], enuv[1]) * R2D; + if (new_cog < 0.0) + { + new_cog += 360.0; + } + this->set_course_over_ground(new_cog); + } + + this->set_time_offset_s(rx_position_and_time[3]); + + DLOG(INFO) << "RTKLIB Position at RX TOW = " << gnss_observables_map.cbegin()->second.RX_time + << " in ECEF (X,Y,Z,t[meters]) = " << rx_position_and_time[0] << ", " << rx_position_and_time[1] << ", " << rx_position_and_time[2] << ", " << rx_position_and_time[3]; + + // gtime_t rtklib_utc_time = gpst2utc(pvt_sol.time); // Corrected RX Time (Non integer multiply of 1 ms of granularity) + // Uncorrected RX Time (integer multiply of 1 ms and the same observables time reported in RTCM and RINEX) + const gtime_t rtklib_time = timeadd(pvt_sol.time, rx_position_and_time[3]); // uncorrected rx time + const gtime_t rtklib_utc_time = gpst2utc(rtklib_time); + boost::posix_time::ptime p_time = boost::posix_time::from_time_t(rtklib_utc_time.time); + p_time += boost::posix_time::microseconds(static_cast(round(rtklib_utc_time.sec * 1e6))); // NOLINT(google-runtime-int) + + this->set_position_UTC_time(p_time); + + DLOG(INFO) << "RTKLIB Position at " << boost::posix_time::to_simple_string(p_time) + << " is Lat = " << this->get_latitude() << " [deg], Long = " << this->get_longitude() + << " [deg], Height= " << this->get_height() << " [m]" + << " RX time offset= " << this->get_time_offset_s() << " [s]"; + + // ######## PVT MONITOR ######### + // TOW + d_monitor_pvt.TOW_at_current_symbol_ms = gnss_observables_map.cbegin()->second.TOW_at_current_symbol_ms; + // WEEK + d_monitor_pvt.week = adjgpsweek(d_nav_data.eph[0].week, this->is_pre_2009()); + // PVT GPS time + d_monitor_pvt.RX_time = gnss_observables_map.cbegin()->second.RX_time; + // User clock offset [s] + d_monitor_pvt.user_clk_offset = rx_position_and_time[3]; + + // ECEF POS X,Y,X [m] + ECEF VEL X,Y,X [m/s] (6 x double) + d_monitor_pvt.pos_x = pvt_sol.rr[0]; + d_monitor_pvt.pos_y = pvt_sol.rr[1]; + d_monitor_pvt.pos_z = pvt_sol.rr[2]; + d_monitor_pvt.vel_x = pvt_sol.rr[3]; + d_monitor_pvt.vel_y = pvt_sol.rr[4]; + d_monitor_pvt.vel_z = pvt_sol.rr[5]; + + // position variance/covariance (m^2) {c_xx,c_yy,c_zz,c_xy,c_yz,c_zx} (6 x double) + d_monitor_pvt.cov_xx = pvt_sol.qr[0]; + d_monitor_pvt.cov_yy = pvt_sol.qr[1]; + d_monitor_pvt.cov_zz = pvt_sol.qr[2]; + d_monitor_pvt.cov_xy = pvt_sol.qr[3]; + d_monitor_pvt.cov_yz = pvt_sol.qr[4]; + d_monitor_pvt.cov_zx = pvt_sol.qr[5]; + + // GEO user position Latitude [deg] + d_monitor_pvt.latitude = this->get_latitude(); + // GEO user position Longitude [deg] + d_monitor_pvt.longitude = this->get_longitude(); + // GEO user position Height [m] + d_monitor_pvt.height = this->get_height(); + + // NUMBER OF VALID SATS + d_monitor_pvt.valid_sats = pvt_sol.ns; + // RTKLIB solution status + d_monitor_pvt.solution_status = pvt_sol.stat; + // RTKLIB solution type (0:xyz-ecef,1:enu-baseline) + d_monitor_pvt.solution_type = pvt_sol.type; + // AR ratio factor for validation + d_monitor_pvt.AR_ratio_factor = pvt_sol.ratio; + // AR ratio threshold for validation + d_monitor_pvt.AR_ratio_threshold = pvt_sol.thres; + + // GDOP / PDOP/ HDOP/ VDOP + d_monitor_pvt.gdop = d_dop[0]; + d_monitor_pvt.pdop = d_dop[1]; + d_monitor_pvt.hdop = d_dop[2]; + d_monitor_pvt.vdop = d_dop[3]; + + this->set_rx_vel({enuv[0], enuv[1], enuv[2]}); + + const double clock_drift_ppm = pvt_sol.dtr[5] / SPEED_OF_LIGHT_M_S * 1e6; + + this->set_clock_drift_ppm(clock_drift_ppm); + // User clock drift [ppm] + d_monitor_pvt.user_clk_drift_ppm = clock_drift_ppm; + + // ######## LOG FILE ######### + if (d_flag_dump_enabled == true) + { + // MULTIPLEXED FILE RECORDING - Record results to file + try + { + double tmp_double; + uint32_t tmp_uint32; + // TOW + tmp_uint32 = gnss_observables_map.cbegin()->second.TOW_at_current_symbol_ms; + d_dump_file.write(reinterpret_cast(&tmp_uint32), sizeof(uint32_t)); + // WEEK + tmp_uint32 = adjgpsweek(d_nav_data.eph[0].week, this->is_pre_2009()); + d_dump_file.write(reinterpret_cast(&tmp_uint32), sizeof(uint32_t)); + // PVT GPS time + tmp_double = gnss_observables_map.cbegin()->second.RX_time; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + // User clock offset [s] + tmp_double = rx_position_and_time[3]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + + // ECEF POS X,Y,X [m] + ECEF VEL X,Y,X [m/s] (6 x double) + tmp_double = pvt_sol.rr[0]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.rr[1]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.rr[2]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.rr[3]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.rr[4]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.rr[5]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + + // position variance/covariance (m^2) {c_xx,c_yy,c_zz,c_xy,c_yz,c_zx} (6 x double) + tmp_double = pvt_sol.qr[0]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.qr[1]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.qr[2]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.qr[3]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.qr[4]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.qr[5]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + + // GEO user position Latitude [deg] + tmp_double = this->get_latitude(); + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + // GEO user position Longitude [deg] + tmp_double = this->get_longitude(); + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + // GEO user position Height [m] + tmp_double = this->get_height(); + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + + // NUMBER OF VALID SATS + d_dump_file.write(reinterpret_cast(&pvt_sol.ns), sizeof(uint8_t)); + // RTKLIB solution status + d_dump_file.write(reinterpret_cast(&pvt_sol.stat), sizeof(uint8_t)); + // RTKLIB solution type (0:xyz-ecef,1:enu-baseline) + d_dump_file.write(reinterpret_cast(&pvt_sol.type), sizeof(uint8_t)); + // AR ratio factor for validation + d_dump_file.write(reinterpret_cast(&pvt_sol.ratio), sizeof(float)); + // AR ratio threshold for validation + d_dump_file.write(reinterpret_cast(&pvt_sol.thres), sizeof(float)); + + // GDOP / PDOP / HDOP / VDOP + d_dump_file.write(reinterpret_cast(&d_dop[0]), sizeof(double)); + d_dump_file.write(reinterpret_cast(&d_dop[1]), sizeof(double)); + d_dump_file.write(reinterpret_cast(&d_dop[2]), sizeof(double)); + d_dump_file.write(reinterpret_cast(&d_dop[3]), sizeof(double)); + } + catch (const std::ofstream::failure &e) + { + LOG(WARNING) << "Exception writing RTKLIB dump file " << e.what(); + } + } + } + } + return this->is_valid_position(); +} From accd9f7c34624154fc597e562b5391f11384c7c2 Mon Sep 17 00:00:00 2001 From: "M.A. Gomez" Date: Wed, 12 Jul 2023 17:27:58 +0200 Subject: [PATCH 09/16] Make clang-format happy --- src/algorithms/PVT/libs/pvt_kf.cc | 59 ++++++++++++++++--------------- 1 file changed, 31 insertions(+), 28 deletions(-) diff --git a/src/algorithms/PVT/libs/pvt_kf.cc b/src/algorithms/PVT/libs/pvt_kf.cc index 17336e0fa..ecd7e7bce 100755 --- a/src/algorithms/PVT/libs/pvt_kf.cc +++ b/src/algorithms/PVT/libs/pvt_kf.cc @@ -42,25 +42,27 @@ void Pvt_Kf::init_Kf(const arma::vec& p, d_H = arma::eye(6, 6); // measurement matrix static covariances - if(estatic_measures_sd){ - d_R = {{pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0, 0.0}, - {0.0, pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0}, - {0.0, 0.0, pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0}, - {0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, - {0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0}, - {0.0, 0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0)}}; + if (estatic_measures_sd) + { + d_R = {{pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, pow(measures_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0)}}; - d_static = true; - - }else{ + d_static = true; + } + else + { d_R = {{res_p[0], res_p[3], res_p[5], 0.0, 0.0, 0.0}, - {res_p[3], res_p[1], res_p[4], 0.0, 0.0, 0.0}, - {res_p[4], res_p[5], res_p[2], 0.0, 0.0, 0.0}, - {0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, - {0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0}, - {0.0, 0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0)}}; + {res_p[3], res_p[1], res_p[4], 0.0, 0.0, 0.0}, + {res_p[4], res_p[5], res_p[2], 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0)}}; - d_static = false; + d_static = false; } // system covariance matrix (static) d_Q = {{pow(system_ecef_pos_sd_m, 2.0), 0.0, 0.0, 0.0, 0.0, 0.0}, @@ -119,18 +121,19 @@ void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res // Measurement update try { - if(!d_static){ - // Measurement residuals update - d_R(0, 0) = res_p[0]; - d_R(0, 1) = res_p[3]; - d_R(0, 2) = res_p[5]; - d_R(1, 0) = res_p[3]; - d_R(1, 1) = res_p[1]; - d_R(1, 2) = res_p[4]; - d_R(2, 0) = res_p[5]; - d_R(2, 1) = res_p[4]; - d_R(2, 2) = res_p[2]; - } + if (!d_static) + { + // Measurement residuals update + d_R(0, 0) = res_p[0]; + d_R(0, 1) = res_p[3]; + d_R(0, 2) = res_p[5]; + d_R(1, 0) = res_p[3]; + d_R(1, 1) = res_p[1]; + d_R(1, 2) = res_p[4]; + d_R(2, 0) = res_p[5]; + d_R(2, 1) = res_p[4]; + d_R(2, 2) = res_p[2]; + } // Measurement update arma::vec z = arma::join_cols(p, v); arma::mat K = d_P_new_old * d_H.t() * arma::inv(d_H * d_P_new_old * d_H.t() + d_R); // Kalman gain From 0b139fa42b14c35b47b503d0d37b6729301a455b Mon Sep 17 00:00:00 2001 From: "M.A. Gomez" Date: Wed, 12 Jul 2023 17:56:00 +0200 Subject: [PATCH 10/16] [ADD] velocity covariance for kf --- src/algorithms/PVT/libs/pvt_kf.cc | 35 ++++++++++----------- src/algorithms/PVT/libs/pvt_kf.h | 4 +-- src/algorithms/PVT/libs/rtklib_solver.cc | 14 +++++---- src/algorithms/libs/rtklib/rtklib_pntpos.cc | 8 +++++ 4 files changed, 34 insertions(+), 27 deletions(-) diff --git a/src/algorithms/PVT/libs/pvt_kf.cc b/src/algorithms/PVT/libs/pvt_kf.cc index ecd7e7bce..281a8473a 100755 --- a/src/algorithms/PVT/libs/pvt_kf.cc +++ b/src/algorithms/PVT/libs/pvt_kf.cc @@ -21,7 +21,7 @@ void Pvt_Kf::init_Kf(const arma::vec& p, const arma::vec& v, - const arma::vec& res_p, + const arma::vec& res_pv, double solver_interval_s, bool estatic_measures_sd, double measures_ecef_pos_sd_m, @@ -55,12 +55,12 @@ void Pvt_Kf::init_Kf(const arma::vec& p, } else { - d_R = {{res_p[0], res_p[3], res_p[5], 0.0, 0.0, 0.0}, - {res_p[3], res_p[1], res_p[4], 0.0, 0.0, 0.0}, - {res_p[4], res_p[5], res_p[2], 0.0, 0.0, 0.0}, - {0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0, 0.0}, - {0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0), 0.0}, - {0.0, 0.0, 0.0, 0.0, 0.0, pow(measures_ecef_vel_sd_ms, 2.0)}}; + d_R = {{res_pv[0], res_pv[3], res_pv[5], 0.0, 0.0, 0.0}, + {res_pv[3], res_pv[1], res_pv[4], 0.0, 0.0, 0.0}, + {res_pv[5], res_pv[4], res_pv[2], 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, res_pv[6], res_pv[9], res_pv[11]}, + {0.0, 0.0, 0.0, res_pv[9], res_pv[7], res_pv[10]}, + {0.0, 0.0, 0.0, res_pv[11], res_pv[10], res_pv[8]}}; d_static = false; } @@ -109,7 +109,7 @@ void Pvt_Kf::reset_Kf() } -void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p) +void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_pv) { if (d_initialized) { @@ -124,17 +124,14 @@ void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res if (!d_static) { // Measurement residuals update - d_R(0, 0) = res_p[0]; - d_R(0, 1) = res_p[3]; - d_R(0, 2) = res_p[5]; - d_R(1, 0) = res_p[3]; - d_R(1, 1) = res_p[1]; - d_R(1, 2) = res_p[4]; - d_R(2, 0) = res_p[5]; - d_R(2, 1) = res_p[4]; - d_R(2, 2) = res_p[2]; - } - // Measurement update + d_R = {{res_pv[0], res_pv[3], res_pv[5], 0.0, 0.0, 0.0}, + {res_pv[3], res_pv[1], res_pv[4], 0.0, 0.0, 0.0}, + {res_pv[5], res_pv[4], res_pv[2], 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, res_pv[6], res_pv[9], res_pv[11]}, + {0.0, 0.0, 0.0, res_pv[9], res_pv[7], res_pv[10]}, + {0.0, 0.0, 0.0, res_pv[11], res_pv[10], res_pv[8]}}; + + } // Measurement update arma::vec z = arma::join_cols(p, v); arma::mat K = d_P_new_old * d_H.t() * arma::inv(d_H * d_P_new_old * d_H.t() + d_R); // Kalman gain diff --git a/src/algorithms/PVT/libs/pvt_kf.h b/src/algorithms/PVT/libs/pvt_kf.h index e051922ee..1c3316613 100755 --- a/src/algorithms/PVT/libs/pvt_kf.h +++ b/src/algorithms/PVT/libs/pvt_kf.h @@ -37,7 +37,7 @@ public: virtual ~Pvt_Kf() = default; void init_Kf(const arma::vec& p, const arma::vec& v, - const arma::vec& res_p, + const arma::vec& res_pv, double solver_interval_s, bool estatic_measures_sd, double measures_ecef_pos_sd_m, @@ -45,7 +45,7 @@ public: double system_ecef_pos_sd_m, double system_ecef_vel_sd_ms); bool is_initialized() const; - void run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_p); + void run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_pv); void get_pv_Kf(arma::vec& p, arma::vec& v) const; void reset_Kf(); diff --git a/src/algorithms/PVT/libs/rtklib_solver.cc b/src/algorithms/PVT/libs/rtklib_solver.cc index 1667eb632..a68ac740a 100755 --- a/src/algorithms/PVT/libs/rtklib_solver.cc +++ b/src/algorithms/PVT/libs/rtklib_solver.cc @@ -1548,12 +1548,13 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ { arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; - arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], - pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; + arma::vec res_pv = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], + pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5], pvt_sol.qvr[0], pvt_sol.qvr[1], pvt_sol.qvr[2], + pvt_sol.qvr[3], pvt_sol.qvr[4], pvt_sol.qvr[5]}; d_pvt_kf.init_Kf(p, v, - res_p, + res_pv, kf_update_interval_s, d_conf.estatic_measures_sd, d_conf.measures_ecef_pos_sd_m, @@ -1565,10 +1566,11 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ { arma::vec p = {pvt_sol.rr[0], pvt_sol.rr[1], pvt_sol.rr[2]}; arma::vec v = {pvt_sol.rr[3], pvt_sol.rr[4], pvt_sol.rr[5]}; - arma::vec res_p = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], - pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5]}; + arma::vec res_pv = {pvt_sol.qr[0], pvt_sol.qr[1], pvt_sol.qr[2], + pvt_sol.qr[3], pvt_sol.qr[4], pvt_sol.qr[5], pvt_sol.qvr[0], pvt_sol.qvr[1], pvt_sol.qvr[2], + pvt_sol.qvr[3], pvt_sol.qvr[4], pvt_sol.qvr[5]}; - d_pvt_kf.run_Kf(p, v, res_p); + d_pvt_kf.run_Kf(p, v, res_pv); d_pvt_kf.get_pv_Kf(p, v); pvt_sol.rr[0] = p[0]; // [m] pvt_sol.rr[1] = p[1]; // [m] diff --git a/src/algorithms/libs/rtklib/rtklib_pntpos.cc b/src/algorithms/libs/rtklib/rtklib_pntpos.cc index 12f39379f..931389470 100644 --- a/src/algorithms/libs/rtklib/rtklib_pntpos.cc +++ b/src/algorithms/libs/rtklib/rtklib_pntpos.cc @@ -1061,6 +1061,14 @@ void estvel(const obsd_t *obs, int n, const double *rs, const double *dts, sol->rr[i + 3] = x[i]; } sol->dtr[5] = x[3]; + + for (j = 0; j < 3; j++) + { + sol->qvr[j] = static_cast(Q[j + j * 4]); + } + sol->qvr[3] = static_cast(Q[1]); /* cov xy */ + sol->qvr[4] = static_cast(Q[2 + 4]); /* cov yz */ + sol->qvr[5] = static_cast(Q[2]); /* cov zx */ break; } } From e8405930334760df38053b40dc72da848c546337 Mon Sep 17 00:00:00 2001 From: "M.A. Gomez" Date: Tue, 18 Jul 2023 19:04:56 +0200 Subject: [PATCH 11/16] Make clang-format happy --- src/algorithms/PVT/libs/pvt_kf.cc | 6 +++--- src/algorithms/PVT/libs/pvt_kf.h | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/algorithms/PVT/libs/pvt_kf.cc b/src/algorithms/PVT/libs/pvt_kf.cc index 281a8473a..f59cdb92f 100755 --- a/src/algorithms/PVT/libs/pvt_kf.cc +++ b/src/algorithms/PVT/libs/pvt_kf.cc @@ -2,6 +2,7 @@ * \file pvt_kf.cc * \brief Kalman Filter for Position and Velocity * \author Javier Arribas, 2023. jarribas(at)cttc.es + * \author Miguel Angel Gomez Lopez, 2023. gomezlma(at)inta.es * * * ----------------------------------------------------------------------------- @@ -123,15 +124,14 @@ void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res { if (!d_static) { - // Measurement residuals update + // Measurement residuals non-static update d_R = {{res_pv[0], res_pv[3], res_pv[5], 0.0, 0.0, 0.0}, {res_pv[3], res_pv[1], res_pv[4], 0.0, 0.0, 0.0}, {res_pv[5], res_pv[4], res_pv[2], 0.0, 0.0, 0.0}, {0.0, 0.0, 0.0, res_pv[6], res_pv[9], res_pv[11]}, {0.0, 0.0, 0.0, res_pv[9], res_pv[7], res_pv[10]}, {0.0, 0.0, 0.0, res_pv[11], res_pv[10], res_pv[8]}}; - - } // Measurement update + } arma::vec z = arma::join_cols(p, v); arma::mat K = d_P_new_old * d_H.t() * arma::inv(d_H * d_P_new_old * d_H.t() + d_R); // Kalman gain diff --git a/src/algorithms/PVT/libs/pvt_kf.h b/src/algorithms/PVT/libs/pvt_kf.h index 1c3316613..000bbd2c4 100755 --- a/src/algorithms/PVT/libs/pvt_kf.h +++ b/src/algorithms/PVT/libs/pvt_kf.h @@ -2,7 +2,7 @@ * \file pvt_kf.h * \brief Kalman Filter for Position and Velocity * \author Javier Arribas, 2023. jarribas(at)cttc.es - * + * \author Miguel Angel Gomez Lopez, 2023. gomezlma(at)inta.es * * ----------------------------------------------------------------------------- * From f886fcd085342b9d2dd9463d8938cd8ff3b151f5 Mon Sep 17 00:00:00 2001 From: "M.A. Gomez" Date: Wed, 12 Jul 2023 18:22:31 +0200 Subject: [PATCH 12/16] [ADD] Velocity covariances to dump file --- src/algorithms/PVT/libs/rtklib_solver.cc | 52 +++++++++++++++++++++++- 1 file changed, 51 insertions(+), 1 deletion(-) diff --git a/src/algorithms/PVT/libs/rtklib_solver.cc b/src/algorithms/PVT/libs/rtklib_solver.cc index a68ac740a..eac9395d0 100755 --- a/src/algorithms/PVT/libs/rtklib_solver.cc +++ b/src/algorithms/PVT/libs/rtklib_solver.cc @@ -194,7 +194,7 @@ bool Rtklib_Solver::save_matfile() const { // READ DUMP FILE const std::string dump_filename = d_dump_filename; - const int32_t number_of_double_vars = 21; + const int32_t number_of_double_vars = 27; const int32_t number_of_uint32_vars = 2; const int32_t number_of_uint8_vars = 3; const int32_t number_of_float_vars = 2; @@ -243,6 +243,12 @@ bool Rtklib_Solver::save_matfile() const auto cov_xy = std::vector(num_epoch); auto cov_yz = std::vector(num_epoch); auto cov_zx = std::vector(num_epoch); + auto cov_vxx = std::vector(num_epoch); + auto cov_vyy = std::vector(num_epoch); + auto cov_vzz = std::vector(num_epoch); + auto cov_vxy = std::vector(num_epoch); + auto cov_vyz = std::vector(num_epoch); + auto cov_vzx = std::vector(num_epoch); auto latitude = std::vector(num_epoch); auto longitude = std::vector(num_epoch); auto height = std::vector(num_epoch); @@ -278,6 +284,12 @@ bool Rtklib_Solver::save_matfile() const dump_file.read(reinterpret_cast(&cov_xy[i]), sizeof(double)); dump_file.read(reinterpret_cast(&cov_yz[i]), sizeof(double)); dump_file.read(reinterpret_cast(&cov_zx[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&cov_vxx[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&cov_vyy[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&cov_vzz[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&cov_vxy[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&cov_vyz[i]), sizeof(double)); + dump_file.read(reinterpret_cast(&cov_vzx[i]), sizeof(double)); dump_file.read(reinterpret_cast(&latitude[i]), sizeof(double)); dump_file.read(reinterpret_cast(&longitude[i]), sizeof(double)); dump_file.read(reinterpret_cast(&height[i]), sizeof(double)); @@ -374,6 +386,30 @@ bool Rtklib_Solver::save_matfile() const Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE Mat_VarFree(matvar); + matvar = Mat_VarCreate("cov_vxx", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_vxx.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("cov_vyy", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_vyy.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("cov_vzz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_vzz.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("cov_vxy", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_vxy.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("cov_vyz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_vyz.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + + matvar = Mat_VarCreate("cov_vzx", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), cov_vzx.data(), 0); + Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE + Mat_VarFree(matvar); + matvar = Mat_VarCreate("latitude", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims.data(), latitude.data(), 0); Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE Mat_VarFree(matvar); @@ -1744,6 +1780,20 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ tmp_double = pvt_sol.qr[5]; d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + // velocity variance/covariance (m^2/s^2) {c_xx,c_yy,c_zz,c_xy,c_yz,c_zx} (6 x double) + tmp_double = pvt_sol.qvr[0]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.qvr[1]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.qvr[2]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.qvr[3]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.qvr[4]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + tmp_double = pvt_sol.qvr[5]; + d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + // GEO user position Latitude [deg] tmp_double = this->get_latitude(); d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); From db6d2427b43e67df258ca46b3cc859a1697ed2b4 Mon Sep 17 00:00:00 2001 From: miguekf Date: Wed, 19 Jul 2023 13:05:55 +0200 Subject: [PATCH 13/16] [ADD] Kiruna location to front-end-cal --- conf/front-end-cal.conf | 22 +++++++++++++--------- 1 file changed, 13 insertions(+), 9 deletions(-) diff --git a/conf/front-end-cal.conf b/conf/front-end-cal.conf index af2a06a2f..29efe2347 100644 --- a/conf/front-end-cal.conf +++ b/conf/front-end-cal.conf @@ -17,19 +17,23 @@ ;GNSS-SDR.init_altitude_m=329.11968943169342 ; Barcelona CTTC -GNSS-SDR.init_latitude_deg=41.27719585553101 -GNSS-SDR.init_longitude_deg=1.988782985790802 -GNSS-SDR.init_altitude_m=10 +;GNSS-SDR.init_latitude_deg=41.27719585553101 +;GNSS-SDR.init_longitude_deg=1.988782985790802 +;GNSS-SDR.init_altitude_m=10 ; Mozoncillo ;GNSS-SDR.init_latitude_deg=41.14534824586196 ;GNSS-SDR.init_longitude_deg=-4.187125019737464 ;GNSS-SDR.init_altitude_m=900 +; ICEBAR - Jukkasjarvi +GNSS-SDR.init_latitude_deg=67.849722 +GNSS-SDR.init_longitude_deg=20.594444 +GNSS-SDR.init_altitude_m=325 ;######### GLOBAL OPTIONS ################## ;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. -GNSS-SDR.internal_fs_sps=2000000 +GNSS-SDR.internal_fs_sps=2048000 ;######### SUPL RRLP GPS assistance configuration ##### ; Check https://www.mcc-mnc.com/ @@ -40,10 +44,10 @@ GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com GNSS-SDR.SUPL_gps_ephemeris_port=7275 GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com GNSS-SDR.SUPL_gps_acquisition_port=7275 -GNSS-SDR.SUPL_MCC=217 -GNSS-SDR.SUPL_MNC=7 -GNSS-SDR.SUPL_LAC=861 -GNSS-SDR.SUPL_CI=40184 +GNSS-SDR.SUPL_MCC=240 +GNSS-SDR.SUPL_MNC=08 +GNSS-SDR.SUPL_LAC=46003 +GNSS-SDR.SUPL_CI=425950 ;######### SIGNAL_SOURCE CONFIG ############ SignalSource.implementation=Osmosdr_Signal_Source @@ -52,7 +56,7 @@ SignalSource.freq=1575420000 ;#item_type: Type and resolution for each of the signal samples. Use only gr_complex in this version. SignalSource.item_type=gr_complex ;#sampling_frequency: Original Signal sampling frequency in samples per second -SignalSource.sampling_frequency=2000000 +SignalSource.sampling_frequency=2048000 ;#gain: Front-end Gain in [dB] SignalSource.gain=40 SignalSource.rf_gain=40 From ccf9527f5498546134fcedd8b0357ad52f842508 Mon Sep 17 00:00:00 2001 From: "M.A. Gomez" Date: Sun, 23 Jul 2023 23:08:37 +0200 Subject: [PATCH 14/16] [ADD] static kalman version --- src/algorithms/PVT/adapters/rtklib_pvt.cc | 1 + src/algorithms/PVT/libs/pvt_conf.h | 1 + src/algorithms/PVT/libs/pvt_kf.cc | 20 +++++++++++++++++++- src/algorithms/PVT/libs/pvt_kf.h | 2 ++ src/algorithms/PVT/libs/rtklib_solver.cc | 1 + 5 files changed, 24 insertions(+), 1 deletion(-) diff --git a/src/algorithms/PVT/adapters/rtklib_pvt.cc b/src/algorithms/PVT/adapters/rtklib_pvt.cc index ad967d953..5ce4cc924 100755 --- a/src/algorithms/PVT/adapters/rtklib_pvt.cc +++ b/src/algorithms/PVT/adapters/rtklib_pvt.cc @@ -76,6 +76,7 @@ Rtklib_Pvt::Rtklib_Pvt(const ConfigurationInterface* configuration, // PVT KF settings pvt_output_parameters.enable_pvt_kf = configuration->property(role + ".enable_pvt_kf", false); + pvt_output_parameters.static_scenario_sd = configuration->property(role + ".static_scenario_sd", false); pvt_output_parameters.estatic_measures_sd = configuration->property(role + ".estatic_measures_sd", false); pvt_output_parameters.measures_ecef_pos_sd_m = configuration->property(role + ".kf_measures_ecef_pos_sd_m", 1.0); pvt_output_parameters.measures_ecef_vel_sd_ms = configuration->property(role + ".kf_measures_ecef_vel_sd_ms", 0.1); diff --git a/src/algorithms/PVT/libs/pvt_conf.h b/src/algorithms/PVT/libs/pvt_conf.h index f194c0596..39bc03e36 100755 --- a/src/algorithms/PVT/libs/pvt_conf.h +++ b/src/algorithms/PVT/libs/pvt_conf.h @@ -97,6 +97,7 @@ public: // PVT KF parameters bool enable_pvt_kf = false; + bool static_scenario_sd = false; bool estatic_measures_sd = false; double measures_ecef_pos_sd_m = 1.0; double measures_ecef_vel_sd_ms = 0.1; diff --git a/src/algorithms/PVT/libs/pvt_kf.cc b/src/algorithms/PVT/libs/pvt_kf.cc index f59cdb92f..aef09efe9 100755 --- a/src/algorithms/PVT/libs/pvt_kf.cc +++ b/src/algorithms/PVT/libs/pvt_kf.cc @@ -24,6 +24,7 @@ void Pvt_Kf::init_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_pv, double solver_interval_s, + bool static_scenario_sd, bool estatic_measures_sd, double measures_ecef_pos_sd_m, double measures_ecef_vel_sd_ms, @@ -32,6 +33,14 @@ void Pvt_Kf::init_Kf(const arma::vec& p, { // Kalman Filter class variables const double Ti = solver_interval_s; + if (static_scenario_sd) + { + scenario_static = true; + } + else + { + scenario_static = false; + } d_F = {{1.0, 0.0, 0.0, Ti, 0.0, 0.0}, {0.0, 1.0, 0.0, 0.0, Ti, 0.0}, @@ -112,6 +121,7 @@ void Pvt_Kf::reset_Kf() void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res_pv) { + // bool static_scenario = true; if (d_initialized) { // Kalman loop @@ -132,7 +142,15 @@ void Pvt_Kf::run_Kf(const arma::vec& p, const arma::vec& v, const arma::vec& res {0.0, 0.0, 0.0, res_pv[9], res_pv[7], res_pv[10]}, {0.0, 0.0, 0.0, res_pv[11], res_pv[10], res_pv[8]}}; } - arma::vec z = arma::join_cols(p, v); + arma::vec z = arma::zeros(6); + if (scenario_static) + { + d_x_new_old[3] = 0; + d_x_new_old[4] = 0; + d_x_new_old[5] = 0; + } + + z = arma::join_cols(p, v); arma::mat K = d_P_new_old * d_H.t() * arma::inv(d_H * d_P_new_old * d_H.t() + d_R); // Kalman gain d_x_new_new = d_x_new_old + K * (z - d_H * d_x_new_old); diff --git a/src/algorithms/PVT/libs/pvt_kf.h b/src/algorithms/PVT/libs/pvt_kf.h index 000bbd2c4..995d19931 100755 --- a/src/algorithms/PVT/libs/pvt_kf.h +++ b/src/algorithms/PVT/libs/pvt_kf.h @@ -39,6 +39,7 @@ public: const arma::vec& v, const arma::vec& res_pv, double solver_interval_s, + bool static_scenario_sd, bool estatic_measures_sd, double measures_ecef_pos_sd_m, double measures_ecef_vel_sd_ms, @@ -63,6 +64,7 @@ private: arma::vec d_x_new_new; bool d_initialized{false}; bool d_static{false}; + bool scenario_static{false}; }; diff --git a/src/algorithms/PVT/libs/rtklib_solver.cc b/src/algorithms/PVT/libs/rtklib_solver.cc index eac9395d0..596bc5fbd 100755 --- a/src/algorithms/PVT/libs/rtklib_solver.cc +++ b/src/algorithms/PVT/libs/rtklib_solver.cc @@ -1592,6 +1592,7 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ v, res_pv, kf_update_interval_s, + d_conf.static_scenario_sd, d_conf.estatic_measures_sd, d_conf.measures_ecef_pos_sd_m, d_conf.measures_ecef_vel_sd_ms, From cfd213c93ac5ef1faefd5c6262dfaac08597c7ec Mon Sep 17 00:00:00 2001 From: miguekf Date: Mon, 24 Jul 2023 10:52:47 +0200 Subject: [PATCH 15/16] [ADD] some extra conf files --- conf/file_GPS_L1_Borio_lab.conf | 127 ++++++++++++++++++++++++++++ conf/noeleec_rtl.conf | 111 +++++++++++++++++++++++++ conf/nooelec_postproc_ishort.conf | 134 ++++++++++++++++++++++++++++++ 3 files changed, 372 insertions(+) create mode 100644 conf/file_GPS_L1_Borio_lab.conf create mode 100644 conf/noeleec_rtl.conf create mode 100644 conf/nooelec_postproc_ishort.conf diff --git a/conf/file_GPS_L1_Borio_lab.conf b/conf/file_GPS_L1_Borio_lab.conf new file mode 100644 index 000000000..bcaa11322 --- /dev/null +++ b/conf/file_GPS_L1_Borio_lab.conf @@ -0,0 +1,127 @@ +[GNSS-SDR] + +; Postprocessing for the file recorded at 2023 JRC GNSS summer school +; Raw IQ file recorded with USRP at JRC ISPRA Laboratory (by Daniele Borio) +; Recorded 10 Mhz Bw at 1575.42 central freq (L1/E1) + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=10000000 +GNSS-SDR.telecommand_enabled=false +GNSS-SDR.telecommand_tcp_port=3333 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=../lab/Gps+Gal+BeiIQ10M8bit0IF09Mar20.bin +SignalSource.item_type=ibyte +SignalSource.sampling_frequency=10000000 +SignalSource.sample_type=iq +SignalSource.samples=0 +SignalSource.enable_throttle_control=false + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner +DataTypeAdapter.implementation=Ibyte_To_Complex +InputFilter.implementation=Pass_Through +InputFilter.item_type=gr_complex +Resampler.implementation=Direct_Resampler +Resampler.sample_freq_in=10000000 +Resampler.sample_freq_out=10000000 +Resampler.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels_1B.count=0 +Channels_L5.count=0 +Channels_5X.count=0 + +Channels.in_acquisition=1 + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.threshold=1.8 +Acquisition_1C.use_CFAR_algorithm=false +Acquisition_1C.blocking=true +Acquisition_1C.doppler_max=6000 +Acquisition_1C.doppler_step=250 + +;Channel0.satellite=12 +;Channel1.satellite=13 +;Channel2.satellite=15 +;Channel3.satellite=17 +;Channel4.satellite=19 +;Channel5.satellite=24 +;Channel6.satellite=28 + +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acquisition/acq_dump.dat +Acquisition_1C.dump_mat=true + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.extend_correlation_symbols=1 + +Tracking_1C.pll_bw_hz=15; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.pll_bw_narrow_hz=5.0; +Tracking_1C.dll_bw_narrow_hz=0.50; +Tracking_1C.fll_bw_hz=10 + +Tracking_1C.enable_fll_pull_in=true; +;Tracking_1C.pull_in_time_s=60 +Tracking_1C.enable_fll_steady_state=false +Tracking_1C.high_dynamics=true +Tracking_1C.dump=false +Tracking_1C.dump_filename=tracking_ch_ + + +Tracking_1C.dump=true +Tracking_1C.dump_filename=./tracking/tracking_raw.dat +Tracking_1C.dump_mat=true + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=true +Observables.dump_mat=true +Observables.dump_filename=./observables/observables_raw.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=OFF ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=OFF ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100; +PVT.display_rate_ms=100; +PVT.elevation_mask=5; +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=true + +PVT.enable_pvt_kf=true +PVT.static_scenario_sd=false + +PVT.estatic_measures_sd=false +PVT.kf_system_ecef_pos_sd_m=0.02 +;PVT.kf_measures_ecef_pos_sd_m=0.00010 + +PVT.kf_system_ecef_vel_sd_ms=0.001 +;PVT.kf_measures_ecef_vel_sd_ms=0.4 + +PVT.dump=true +PVT.dump_mat=true +PVT.dump_filename=./PVT_raw + +PVT.gpx_output_enabled=false +PVT.geojson_output_enabled=false +PVT.kml_output_enabled=false +PVT.xml_output_enabled=false +PVT.rinex_output_enabled=false +PVT.nmea_output_file_enabled=false diff --git a/conf/noeleec_rtl.conf b/conf/noeleec_rtl.conf new file mode 100644 index 000000000..c99949724 --- /dev/null +++ b/conf/noeleec_rtl.conf @@ -0,0 +1,111 @@ +[GNSS-SDR] + + +; RealTime configuration for Nooeleec RTL Software defined radio receiver +; 2023 JRC GNSS summer school + + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=2048000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Osmosdr_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.sampling_frequency=2048000 +SignalSource.freq=1575420000 +SignalSource.gain=40 +SignalSource.rf_gain=40 +SignalSource.if_gain=30 +SignalSource.AGC_enabled=false +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=true +SignalSource.dump_filename=./signal_source.dat +SignalSource.enable_throttle_control=false + +;# Please note that the new RTL-SDR Blog V3 dongles ship a < 1 PPM +;# temperature compensated oscillator (TCXO), which is well suited for GNSS +;# signal processing, and a 4.5 V powered bias-tee to feed an active antenna. +;# Whether the bias-tee is turned off before reception depends on which version +;# of gr-osmosdr was used when compiling GNSS-SDR. With an old version +;# (for example, v0.1.4-8), the utility rtl_biast may be used to switch the +;# bias-tee, and then call gnss-sdr. +;# See https://github.com/rtlsdrblog/rtl_biast +;# After reception the bias-tee is switched off automatically by the program. +;# With newer versions of gr-osmosdr (>= 0.1.4-13), the bias-tee can be +;# activated by uncommenting the following line: +SignalSource.osmosdr_args=rtl,bias=1 + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=7 +Channels_1B.count=0 +Channels.in_acquisition=1 +Channel.signal=1C +;Channel0.satellite=8 +;Channel1.satellite=13 +;Channel2.satellite=14 +;Channel3.satellite=15 +;Channel4.satellite=23 +;Channel5.satellite=27 + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +;Acquisition_1C.threshold=2.0 +Acquisition_1C.use_CFAR_algorithm=false +Acquisition_1C.blocking=false +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ +Tracking_1C.pll_bw_hz=35.0; +Tracking_1C.dll_bw_hz=1.5; +Tracking_1C.pll_bw_narrow_hz=2.5; +Tracking_1C.dll_bw_narrow_hz=0.5; +Tracking_1C.extend_correlation_symbols=1; +Tracking_1C.dll_filter_order=2; +Tracking_1C.pll_filter_order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.early_late_space_narrow_chips=0.25 + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat +Observables.enable_carrier_smoothing=false +Observables.smoothing_factor=200 + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.enable_rx_clock_correction=false +PVT.output_rate_ms=100 +PVT.rinexobs_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.dump=false +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 + + diff --git a/conf/nooelec_postproc_ishort.conf b/conf/nooelec_postproc_ishort.conf new file mode 100644 index 000000000..b15c84896 --- /dev/null +++ b/conf/nooelec_postproc_ishort.conf @@ -0,0 +1,134 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; Postprocessing for the file recorded at 2023 JRC GNSS summer school +; Raw IQ file recorded with Nooeleec RTL Software defined radio receiver +; Recorded 2.048 Mhz Bw at 1575.42 central freq (L1/E1) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2048000 + +;######### CONTROL_THREAD CONFIG ############ +ControlThread.wait_for_flowgraph=false + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=./Kiruna_summer_school_noeleec.dat; +SignalSource.item_type=gr_complex +SignalSource.sampling_frequency=2048000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through;Ishort_To_Complex + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Pass_Through +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Direct_Resampler +Resampler.sample_freq_in=2048000 +Resampler.sample_freq_out=2048000 +Resampler.item_type=gr_complex + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=0 +Channels_1B.count=8 +Channels.in_acquisition=1 +Channel.signal=1B +;#signal: +;# "1C" GPS L1 C/A +;# "1B" GALILEO E1 B (I/NAV OS/CS/SoL) +;# "1G" GLONASS L1 C/A +;# "2S" GPS L2 L2C (M) +;# "5X" GALILEO E5a I+Q +;# "L5" GPS L5 + + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.threshold=3.5 +Acquisition_1C.blocking=true +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### GALILEO ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.threshold=2.5 +Acquisition_1B.blocking=true +Acquisition_1B.doppler_max=5000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.extend_correlation_ms=1 +Tracking_1C.pll_bw_hz=40; +Tracking_1C.pll_bw_narrow_hz=30; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.dll_bw_narrow_hz=1.5; +Tracking_1C.order=2; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TRACKING GALILEO CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=15.0; +Tracking_1B.dll_bw_hz=3.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + +;######### TELEMETRY DECODER GALILEO CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=true +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false From 6ad3d0fa3279a2d83d0997e3e6e4de5f1316525a Mon Sep 17 00:00:00 2001 From: miguekf Date: Sun, 15 Oct 2023 22:42:10 +0200 Subject: [PATCH 16/16] [MOD] tidy config files --- conf/File_input/gnss-sdr-L1-gaussian.conf | 67 +++ conf/File_input/gnss-sdr.conf | 145 +++++++ conf/File_input/gnss-sdr_BDS_B1I_byte.conf | 127 ++++++ .../gnss-sdr_BDS_B3I_GPS_L1_CA_ibyte.conf | 212 ++++++++++ conf/File_input/gnss-sdr_BDS_B3I_byte.conf | 123 ++++++ conf/File_input/gnss-sdr_BDS_B3I_ibyte.conf | 132 ++++++ conf/File_input/gnss-sdr_BDS_B3I_short.conf | 81 ++++ ...nss-sdr_GLONASS_L1_CA_GPS_L1_CA_ibyte.conf | 142 +++++++ .../gnss-sdr_GLONASS_L1_CA_GPS_L2C_ibyte.conf | 143 +++++++ .../gnss-sdr_GLONASS_L1_CA_ibyte.conf | 82 ++++ .../gnss-sdr_GLONASS_L1_CA_ibyte_coh_trk.conf | 86 ++++ .../File_input/gnss-sdr_GLONASS_L1_ibyte.conf | 101 +++++ ...nss-sdr_GLONASS_L2_CA_GPS_L1_CA_ibyte.conf | 143 +++++++ .../gnss-sdr_GLONASS_L2_CA_GPS_L2C_ibyte.conf | 144 +++++++ .../gnss-sdr_GLONASS_L2_CA_ibyte.conf | 76 ++++ .../gnss-sdr_GLONASS_L2_CA_ibyte_coh_trk.conf | 86 ++++ conf/File_input/gnss-sdr_GPS_L1_CA_ibyte.conf | 94 +++++ conf/File_input/gnss-sdr_GPS_L1_SPIR.conf | 137 +++++++ .../gnss-sdr_GPS_L1_acq_QuickSync.conf | 108 +++++ .../gnss-sdr_GPS_L1_gr_complex.conf | 98 +++++ conf/File_input/gnss-sdr_GPS_L1_ishort.conf | 102 +++++ .../gnss-sdr_Galileo_E1_acq_QuickSync.conf | 100 +++++ .../gnss-sdr_Galileo_E1_ishort.conf | 109 +++++ conf/File_input/gnss-sdr_Galileo_E1_nsr.conf | 127 ++++++ conf/File_input/gnss-sdr_Galileo_E5a.conf | 121 ++++++ .../gnss-sdr_Galileo_E5a_IFEN_CTTC.conf | 157 +++++++ conf/File_input/gnss-sdr_Hybrid_byte.conf | 160 ++++++++ conf/File_input/gnss-sdr_Hybrid_byte_sim.conf | 145 +++++++ .../gnss-sdr_Hybrid_gr_complex.conf | 131 ++++++ conf/File_input/gnss-sdr_Hybrid_ishort.conf | 161 ++++++++ ...r_galileo_E1_extended_correlator_byte.conf | 141 +++++++ ...galileo_E1_extended_correlator_labsat.conf | 169 ++++++++ conf/File_input/gnss-sdr_labsat_kf.conf | 185 +++++++++ ...nnel_GPS_L1_Flexiband_bin_file_III_1a.conf | 184 +++++++++ ...nnel_GPS_L1_Flexiband_realtime_III_1a.conf | 189 +++++++++ ...nnel_GPS_L1_Flexiband_realtime_III_1b.conf | 188 +++++++++ ...annel_GPS_L1_Flexiband_realtime_II_3b.conf | 195 +++++++++ ...hannel_GPS_L1_Flexiband_realtime_I_1b.conf | 183 +++++++++ ...l_GPS_L1_L2_Flexiband_realtime_III_1b.conf | 305 ++++++++++++++ ...Galileo_E1B_Flexiband_bin_file_III_1b.conf | 278 +++++++++++++ ...el_GPS_L2_M_Flexiband_bin_file_III_1b.conf | 363 +++++++++++++++++ ...S_L2_M_Flexiband_bin_file_III_1b_real.conf | 258 ++++++++++++ ..._all_in_one_Flexiband_bin_file_III_1b.conf | 385 ++++++++++++++++++ .../gnss-sdr_multisource_Hybrid_ishort.conf | 169 ++++++++ .../gnss-sdr_multisource_Hybrid_nsr.conf | 231 +++++++++++ conf/Nsr_input/gnss-sdr_GPS_L1_nsr.conf | 164 ++++++++ conf/Nsr_input/gnss-sdr_GPS_L1_nsr_gauss.conf | 207 ++++++++++ conf/Nsr_input/gnss-sdr_Hybrid_nsr.conf | 176 ++++++++ conf/Other/front-end-cal.conf | 206 ++++++++++ conf/Other/gnss-sdr_GPS_L1_2ch_udp.conf | 103 +++++ conf/Other/gnss-sdr_GPS_L1_FPGA.conf | 72 ++++ conf/Other/gnss-sdr_GPS_L1_fifo.conf | 56 +++ .../Other/gnss-sdr_GPS_L1_gr_complex_gpu.conf | 85 ++++ conf/Other/gnss-sdr_GPS_L1_monitor.conf | 89 ++++ .../gnss-sdr_GPS_L1_nsr_twobit_packed.conf | 154 +++++++ ...-sdr_GPS_L1_pulse_blanking_gr_complex.conf | 111 +++++ conf/Other/gnss-sdr_GPS_L1_two_bits_cpx.conf | 138 +++++++ .../gnss-sdr_GPS_L1_udp_with_monitor.conf | 82 ++++ ...gnss-sdr_GPS_L1_2ch_fmcomms2_realtime.conf | 115 ++++++ .../gnss-sdr_GPS_L1_LimeSDR.conf | 129 ++++++ .../gnss-sdr_GPS_L1_USRP_X300_realtime.conf | 157 +++++++ .../gnss-sdr_GPS_L1_USRP_realtime.conf | 118 ++++++ .../gnss-sdr_GPS_L1_bladeRF.conf | 109 +++++ .../gnss-sdr_GPS_L1_fmcomms2_realtime.conf | 134 ++++++ .../gnss-sdr_GPS_L1_plutosdr_realtime.conf | 145 +++++++ .../gnss-sdr_GPS_L1_rtl_tcp_realtime.conf | 151 +++++++ .../gnss-sdr_GPS_L1_rtlsdr_realtime.conf | 153 +++++++ .../gnss-sdr_GPS_L2C_USRP1_realtime.conf | 156 +++++++ .../gnss-sdr_GPS_L2C_USRP_X300_realtime.conf | 162 ++++++++ ...nss-sdr_Galileo_E1_USRP_X300_realtime.conf | 93 +++++ ...ultichannel_GPS_L1_USRP_X300_realtime.conf | 161 ++++++++ 71 files changed, 10489 insertions(+) create mode 100644 conf/File_input/gnss-sdr-L1-gaussian.conf create mode 100644 conf/File_input/gnss-sdr.conf create mode 100644 conf/File_input/gnss-sdr_BDS_B1I_byte.conf create mode 100644 conf/File_input/gnss-sdr_BDS_B3I_GPS_L1_CA_ibyte.conf create mode 100644 conf/File_input/gnss-sdr_BDS_B3I_byte.conf create mode 100644 conf/File_input/gnss-sdr_BDS_B3I_ibyte.conf create mode 100644 conf/File_input/gnss-sdr_BDS_B3I_short.conf create mode 100644 conf/File_input/gnss-sdr_GLONASS_L1_CA_GPS_L1_CA_ibyte.conf create mode 100644 conf/File_input/gnss-sdr_GLONASS_L1_CA_GPS_L2C_ibyte.conf create mode 100644 conf/File_input/gnss-sdr_GLONASS_L1_CA_ibyte.conf create mode 100644 conf/File_input/gnss-sdr_GLONASS_L1_CA_ibyte_coh_trk.conf create mode 100644 conf/File_input/gnss-sdr_GLONASS_L1_ibyte.conf create mode 100644 conf/File_input/gnss-sdr_GLONASS_L2_CA_GPS_L1_CA_ibyte.conf create mode 100644 conf/File_input/gnss-sdr_GLONASS_L2_CA_GPS_L2C_ibyte.conf create mode 100644 conf/File_input/gnss-sdr_GLONASS_L2_CA_ibyte.conf create mode 100644 conf/File_input/gnss-sdr_GLONASS_L2_CA_ibyte_coh_trk.conf create mode 100644 conf/File_input/gnss-sdr_GPS_L1_CA_ibyte.conf create mode 100644 conf/File_input/gnss-sdr_GPS_L1_SPIR.conf create mode 100644 conf/File_input/gnss-sdr_GPS_L1_acq_QuickSync.conf create mode 100644 conf/File_input/gnss-sdr_GPS_L1_gr_complex.conf create mode 100644 conf/File_input/gnss-sdr_GPS_L1_ishort.conf create mode 100644 conf/File_input/gnss-sdr_Galileo_E1_acq_QuickSync.conf create mode 100644 conf/File_input/gnss-sdr_Galileo_E1_ishort.conf create mode 100644 conf/File_input/gnss-sdr_Galileo_E1_nsr.conf create mode 100644 conf/File_input/gnss-sdr_Galileo_E5a.conf create mode 100644 conf/File_input/gnss-sdr_Galileo_E5a_IFEN_CTTC.conf create mode 100644 conf/File_input/gnss-sdr_Hybrid_byte.conf create mode 100644 conf/File_input/gnss-sdr_Hybrid_byte_sim.conf create mode 100644 conf/File_input/gnss-sdr_Hybrid_gr_complex.conf create mode 100644 conf/File_input/gnss-sdr_Hybrid_ishort.conf create mode 100644 conf/File_input/gnss-sdr_galileo_E1_extended_correlator_byte.conf create mode 100644 conf/File_input/gnss-sdr_galileo_E1_extended_correlator_labsat.conf create mode 100644 conf/File_input/gnss-sdr_labsat_kf.conf create mode 100644 conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_bin_file_III_1a.conf create mode 100644 conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_III_1a.conf create mode 100644 conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_III_1b.conf create mode 100644 conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_II_3b.conf create mode 100644 conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_I_1b.conf create mode 100644 conf/File_input/gnss-sdr_multichannel_GPS_L1_L2_Flexiband_realtime_III_1b.conf create mode 100644 conf/File_input/gnss-sdr_multichannel_GPS_L1_L2_Galileo_E1B_Flexiband_bin_file_III_1b.conf create mode 100644 conf/File_input/gnss-sdr_multichannel_GPS_L2_M_Flexiband_bin_file_III_1b.conf create mode 100644 conf/File_input/gnss-sdr_multichannel_GPS_L2_M_Flexiband_bin_file_III_1b_real.conf create mode 100644 conf/File_input/gnss-sdr_multichannel_all_in_one_Flexiband_bin_file_III_1b.conf create mode 100644 conf/File_input/gnss-sdr_multisource_Hybrid_ishort.conf create mode 100644 conf/File_input/gnss-sdr_multisource_Hybrid_nsr.conf create mode 100644 conf/Nsr_input/gnss-sdr_GPS_L1_nsr.conf create mode 100644 conf/Nsr_input/gnss-sdr_GPS_L1_nsr_gauss.conf create mode 100644 conf/Nsr_input/gnss-sdr_Hybrid_nsr.conf create mode 100644 conf/Other/front-end-cal.conf create mode 100644 conf/Other/gnss-sdr_GPS_L1_2ch_udp.conf create mode 100644 conf/Other/gnss-sdr_GPS_L1_FPGA.conf create mode 100644 conf/Other/gnss-sdr_GPS_L1_fifo.conf create mode 100644 conf/Other/gnss-sdr_GPS_L1_gr_complex_gpu.conf create mode 100644 conf/Other/gnss-sdr_GPS_L1_monitor.conf create mode 100644 conf/Other/gnss-sdr_GPS_L1_nsr_twobit_packed.conf create mode 100644 conf/Other/gnss-sdr_GPS_L1_pulse_blanking_gr_complex.conf create mode 100644 conf/Other/gnss-sdr_GPS_L1_two_bits_cpx.conf create mode 100644 conf/Other/gnss-sdr_GPS_L1_udp_with_monitor.conf create mode 100644 conf/RealTime_input/gnss-sdr_GPS_L1_2ch_fmcomms2_realtime.conf create mode 100644 conf/RealTime_input/gnss-sdr_GPS_L1_LimeSDR.conf create mode 100644 conf/RealTime_input/gnss-sdr_GPS_L1_USRP_X300_realtime.conf create mode 100644 conf/RealTime_input/gnss-sdr_GPS_L1_USRP_realtime.conf create mode 100644 conf/RealTime_input/gnss-sdr_GPS_L1_bladeRF.conf create mode 100644 conf/RealTime_input/gnss-sdr_GPS_L1_fmcomms2_realtime.conf create mode 100644 conf/RealTime_input/gnss-sdr_GPS_L1_plutosdr_realtime.conf create mode 100644 conf/RealTime_input/gnss-sdr_GPS_L1_rtl_tcp_realtime.conf create mode 100644 conf/RealTime_input/gnss-sdr_GPS_L1_rtlsdr_realtime.conf create mode 100644 conf/RealTime_input/gnss-sdr_GPS_L2C_USRP1_realtime.conf create mode 100644 conf/RealTime_input/gnss-sdr_GPS_L2C_USRP_X300_realtime.conf create mode 100644 conf/RealTime_input/gnss-sdr_Galileo_E1_USRP_X300_realtime.conf create mode 100644 conf/RealTime_input/gnss-sdr_multichannel_GPS_L1_USRP_X300_realtime.conf diff --git a/conf/File_input/gnss-sdr-L1-gaussian.conf b/conf/File_input/gnss-sdr-L1-gaussian.conf new file mode 100644 index 000000000..a208366e5 --- /dev/null +++ b/conf/File_input/gnss-sdr-L1-gaussian.conf @@ -0,0 +1,67 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2000000 +GNSS-SDR.internal_fs_hz=2000000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/home/glamountain/gnss-sdr/data/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat +SignalSource.item_type=ishort +SignalSource.sampling_frequency=4000000 +SignalSource.freq=1575420000 +SignalSource.samples=0 + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner +DataTypeAdapter.implementation=Ishort_To_Complex +InputFilter.implementation=Pass_Through +InputFilter.item_type=gr_complex +Resampler.implementation=Direct_Resampler +Resampler.sample_freq_in=4000000 +Resampler.sample_freq_out=2000000 +Resampler.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels.in_acquisition=1 +Channel.signal=1C + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=../data/kalman/acq_dump + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_Gaussian_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=4.0; +Tracking_1C.order=3; +Tracking_1C.dump=true +Tracking_1C.dump_filename=../data/kalman/epl_tracking_ch_ +Tracking_1C.bce_run = true; +Tracking_1C.p_transient = 0; +Tracking_1C.s_transient = 100; + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=GPS_L1_CA_Observables + +;######### PVT CONFIG ############ +PVT.implementation=GPS_L1_CA_PVT +PVT.averaging_depth=100 +PVT.flag_averaging=true +PVT.output_rate_ms=10 +PVT.display_rate_ms=500 diff --git a/conf/File_input/gnss-sdr.conf b/conf/File_input/gnss-sdr.conf new file mode 100644 index 000000000..3f4b61766 --- /dev/null +++ b/conf/File_input/gnss-sdr.conf @@ -0,0 +1,145 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; Default configuration file +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/datalogger/signals/CTTC/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=ishort +SignalSource.sampling_frequency=4000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Ishort_To_Complex + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Pass_Through ; or Fir_Filter + +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.44 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=4000000 +InputFilter.IF=0 +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=6 +Channels_1B.count=0 +Channels.in_acquisition=1 + + +;######### SPECIFIC CHANNELS CONFIG ###### + +;######### CHANNEL 0 CONFIG ############ +;Channel0.signal=1C +;Channel0.satellite=11 + +;######### CHANNEL 1 CONFIG ############ +;Channel1.signal=1C +;Channel1.satellite=18 + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition_Fine_Doppler +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=2.5 +;Acquisition_1C.pfa=0.0001 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.max_dwells=5 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=45.0; +Tracking_1C.dll_bw_hz=3.0; +Tracking_1C.order=3; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.AR_GPS=PPP-AR ; options: OFF, Continuous, Instantaneous, Fix-and-Hold, PPP-AR +PVT.output_rate_ms=10 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea +PVT.flag_nmea_tty_port=true +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_BDS_B1I_byte.conf b/conf/File_input/gnss-sdr_BDS_B1I_byte.conf new file mode 100644 index 000000000..a21547d24 --- /dev/null +++ b/conf/File_input/gnss-sdr_BDS_B1I_byte.conf @@ -0,0 +1,127 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=25000000 + +;######### CONTROL_THREAD CONFIG ############ +ControlThread.wait_for_flowgraph=false + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/archive/BDS3_datasets/BdsB1IStr01.dat +SignalSource.item_type=byte +SignalSource.sampling_frequency=25000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.enable_throttle_control=false + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner +DataTypeAdapter.implementation=Byte_To_Short +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.input_item_type=short +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.70 +InputFilter.band2_begin=0.80 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=25000000 +InputFilter.IF=6250000 +InputFilter.dump = false +InputFilter.dump_filename=/home/dmiralles/Documents/gnss-sdr/src/tests/signal_samples/BdsB1IStr01_fs25e6_if0_4ms.dat +Resampler.implementation=Pass_Through +Resampler.sample_freq_in=25000000 +Resampler.sample_freq_out=25000000 +Resampler.item_type=gr_complex + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_B1.count=10 +Channels.in_acquisition=1 +Channel.signal=B1 + +Channel0.satellite = 6; +Channel1.satellite = 8; +Channel2.satellite = 9; +Channel3.satellite = 13; +Channel4.satellite = 17; +Channel5.satellite = 1; +Channel6.satellite = 2; +Channel7.satellite = 3; +Channel8.satellite = 4; +Channel9.satellite = 5; + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_B1.implementation=BEIDOU_B1I_PCPS_Acquisition +Acquisition_B1.item_type=gr_complex +Acquisition_B1.coherent_integration_time_ms=1 +Acquisition_B1.pfa=0.01 +;Acquisition_B1.pfa=0.0000001; +Acquisition_B1.doppler_max=10000 +Acquisition_B1.doppler_step=100 +Acquisition_B1.dump=true +Acquisition_B1.dump_filename=./bds_acq +Acquisition_B1.blocking=false; +Acquisition_B1.bit_transition_flag = false; + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_B1.implementation=BEIDOU_B1I_DLL_PLL_Tracking +Tracking_B1.item_type=gr_complex +Tracking_B1.pll_bw_hz=25.0; +Tracking_B1.dll_bw_hz=2.50; +Tracking_B1.dump=false; +Tracking_B1.dump_filename=./epl_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_B1.implementation=BEIDOU_B1I_Telemetry_Decoder +TelemetryDecoder_B1.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=true +PVT.rinex_version=3 +PVT.rinex_output_enabled=true +PVT.gpx_output_enabled=true diff --git a/conf/File_input/gnss-sdr_BDS_B3I_GPS_L1_CA_ibyte.conf b/conf/File_input/gnss-sdr_BDS_B3I_GPS_L1_CA_ibyte.conf new file mode 100644 index 000000000..f6df123ee --- /dev/null +++ b/conf/File_input/gnss-sdr_BDS_B3I_GPS_L1_CA_ibyte.conf @@ -0,0 +1,212 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=30000000 +GNSS-SDR.num_sources=2 + +;######### CONTROL_THREAD CONFIG ############ +ControlThread.wait_for_flowgraph=false + +;######### SIGNAL_SOURCE CONFIG ############ +;# Signal Source config for GPS, Galileo signals +SignalSource0.implementation=File_Signal_Source +SignalSource0.filename=/archive/BDS3_datasets/long/20180713_211400_3.dat +SignalSource0.item_type=ibyte +SignalSource0.sampling_frequency=10000000 +SignalSource0.samples=0 +SignalSource0.repeat=false +SignalSource0.dump=false +SignalSource0.enable_throttle_control=false + +;# Signal Source config for BDS signals +SignalSource1.implementation=File_Signal_Source +SignalSource1.filename=/archive/BDS3_datasets/long/20180713_211400_2.dat +SignalSource1.item_type=ibyte +SignalSource1.sampling_frequency=30000000 +SignalSource1.samples=0 +SignalSource1.repeat=false +SignalSource1.dump=false +SignalSource1.enable_throttle_control=false + +;######### SIGNAL_CONDITIONER CONFIG ############ +;# Signal Conditioner config for GPS, Galileo signals +SignalConditioner0.implementation=Signal_Conditioner +DataTypeAdapter0.implementation=Ibyte_To_Complex +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.70 +InputFilter0.band2_begin=0.80 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=10000000 +InputFilter0.IF=420000 +Resampler0.implementation=Direct_Resampler +Resampler0.sample_freq_in=10000000 +Resampler0.sample_freq_out=30000000 +Resampler0.item_type=gr_complex + +;# Signal Conditioner config for BDS signals +SignalConditioner1.implementation=Signal_Conditioner +DataTypeAdapter1.implementation=Ibyte_To_Complex +InputFilter1.implementation=Freq_Xlating_Fir_Filter +InputFilter1.input_item_type=gr_complex +InputFilter1.output_item_type=gr_complex +InputFilter1.taps_item_type=float +InputFilter1.number_of_taps=5 +InputFilter1.number_of_bands=2 +InputFilter1.band1_begin=0.0 +InputFilter1.band1_end=0.70 +InputFilter1.band2_begin=0.80 +InputFilter1.band2_end=1.0 +InputFilter1.ampl1_begin=1.0 +InputFilter1.ampl1_end=1.0 +InputFilter1.ampl2_begin=0.0 +InputFilter1.ampl2_end=0.0 +InputFilter1.band1_error=1.0 +InputFilter1.band2_error=1.0 +InputFilter1.filter_type=bandpass +InputFilter1.grid_density=16 +InputFilter1.sampling_frequency=10000000 +InputFilter1.IF=1020000 +Resampler1.implementation=Pass_Through +Resampler1.sample_freq_in=30000000 +Resampler1.sample_freq_out=30000000 +Resampler1.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=7 +Channels_B3.count=4 +Channels.in_acquisition=11 + +;# Preparing collection for GPS satellites +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +Channel4.RF_channel_ID=0 +Channel5.RF_channel_ID=0 +Channel6.RF_channel_ID=0 +Channel0.signal=1C +Channel0.satellite = 2 +Channel1.signal=1C +Channel1.satellite = 5 +Channel2.signal=1C +Channel2.satellite = 25 +Channel3.signal=1C +Channel3.satellite = 31 +Channel4.signal=1C +Channel4.satellite = 24 +Channel5.signal=1C +Channel5.satellite = 6 +Channel6.signal=1C +Channel6.satellite = 29 + +;# Preparing collection for BDS satellites +Channel7.RF_channel_ID=1 +Channel8.RF_channel_ID=1 +Channel9.RF_channel_ID=1 +Channel10.RF_channel_ID=1 + +Channel7.signal=B3 +Channel7.satellite = 29 +Channel8.signal=B3 +Channel8.satellite = 19 +Channel9.signal=B3 +Channel9.satellite = 20 +Channel10.signal=B3 +Channel10.satellite = 30 + + +;######### ACQUISITION GLOBAL CONFIG ############ +;# Acquisition config for BDS signals +Acquisition_B3.implementation=BEIDOU_B3I_PCPS_Acquisition +Acquisition_B3.item_type=gr_complex +Acquisition_B3.coherent_integration_time_ms=1 +Acquisition_B3.pfa=0.01 +Acquisition_B3.doppler_max=15000 +Acquisition_B3.doppler_step=50 +Acquisition_B3.dump=false +Acquisition_B3.dump_filename=/home/dmiralles/Documents/Research/Publications/INSIDE_GNSS/bds_leg_pvt/Data/bds_b1i_acq +Acquisition_B3.blocking=false; +Acquisition_B3.use_CFAR_algorithm=true; +Acquisition_B3.bit_transition_flag = false; + +;# Acquisition config for GPS signals +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=15000 +Acquisition_1C.doppler_step=50 +Acquisition_1C.dump=true +Acquisition_1C.dump_filename=/home/dmiralles/Documents/Research/Publications/INSIDE_GNSS/bds_leg_pvt/Data/gps_l1ca_acq +Acquisition_1C.blocking=false; +Acquisition_1C.use_CFAR_algorithm=true; +Acquisition_1C.bit_transition_flag = false; + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_B3.implementation=BEIDOU_B3I_DLL_PLL_Tracking +Tracking_B3.item_type=gr_complex +Tracking_B3.pll_bw_hz=25.0; +Tracking_B3.dll_bw_hz=2.50; +Tracking_B3.dump=true; +Tracking_B3.dump_filename=/home/dmiralles/Documents/Research/Publications/INSIDE_GNSS/bds_leg_pvt/Data/bds_b1i_trk_ch_ + +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=25.0; +Tracking_1C.dll_bw_hz=2.50; +Tracking_1C.dump=true; +Tracking_1C.dump_filename=/home/dmiralles/Documents/Research/Publications/INSIDE_GNSS/bds_leg_pvt/Data/gps_l1ca_trk_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_B3.implementation=BEIDOU_B3I_Telemetry_Decoder +TelemetryDecoder_B3.dump=false + +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=true +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=OFF ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump=true +PVT.dump_filename = /home/dmiralles/Documents/Research/Publications/INSIDE_GNSS/bds_leg_pvt/Data/pvt_l1 +PVT.kml_output_enabled = false; +PVT.xml_output_enabled = false; +PVT.gpx_output_enabled = false; +PVT.rinex_output_enabled = false; +PVT.rtcm_output_enabled = false; +PVT.nmea_output_enabled = false; +PVT.geojson_output_enabled = false; diff --git a/conf/File_input/gnss-sdr_BDS_B3I_byte.conf b/conf/File_input/gnss-sdr_BDS_B3I_byte.conf new file mode 100644 index 000000000..8de1c685e --- /dev/null +++ b/conf/File_input/gnss-sdr_BDS_B3I_byte.conf @@ -0,0 +1,123 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=50000000 + +;######### CONTROL_THREAD CONFIG ############ +ControlThread.wait_for_flowgraph=false + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/archive/BDS3_datasets/BdsB3IStr01.dat +SignalSource.item_type=byte +SignalSource.sampling_frequency=50000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.enable_throttle_control=false +;SignalSource.samples=200000 + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner +DataTypeAdapter.implementation=Byte_To_Short +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.input_item_type=short +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.70 +InputFilter.band2_begin=0.80 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=50000000 +InputFilter.IF=12500000 +InputFilter.dump = false +InputFilter.dump_filename=/home/dmiralles/Documents/gnss-sdr/src/tests/signal_samples/BdsB3IStr01_fs50e6_if0_4ms.dat +Resampler.implementation=Pass_Through +Resampler.sample_freq_in=50000000 +Resampler.sample_freq_out=50000000 +Resampler.item_type=gr_complex + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_B3.count=10 +Channels.in_acquisition=1 +Channel.signal=B3 + +Channel0.satellite = 6; +Channel1.satellite = 23; +Channel2.satellite = 16; +Channel3.satellite = 18; +Channel4.satellite = 7; +Channel5.satellite = 1; +Channel6.satellite = 2; +Channel7.satellite = 3; +Channel8.satellite = 4; +Channel9.satellite = 5; + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_B3.implementation=BEIDOU_B3I_PCPS_Acquisition +Acquisition_B3.item_type=gr_complex +Acquisition_B3.coherent_integration_time_ms=3 +Acquisition_B3.max_dwells = 2 +Acquisition_B3.pfa=0.01 +Acquisition_B3.doppler_max=10000 +Acquisition_B3.doppler_step=100 +Acquisition_B3.dump=false +Acquisition_B3.dump_filename=./bds_acq + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_B3.implementation=BEIDOU_B3I_DLL_PLL_Tracking +Tracking_B3.item_type=gr_complex +Tracking_B3.pll_bw_hz=40.0; +Tracking_B3.dll_bw_hz=4.0; +Tracking_B3.pll_bw_narrow_hz=20.0; +Tracking_B3.dll_bw_narrow_hz=3.0; +Tracking_B3.dump=false; +Tracking_B3.dump_filename=./epl_tracking_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_B3.implementation=BEIDOU_B3I_Telemetry_Decoder +TelemetryDecoder_B3.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=true diff --git a/conf/File_input/gnss-sdr_BDS_B3I_ibyte.conf b/conf/File_input/gnss-sdr_BDS_B3I_ibyte.conf new file mode 100644 index 000000000..b8d1e9cb5 --- /dev/null +++ b/conf/File_input/gnss-sdr_BDS_B3I_ibyte.conf @@ -0,0 +1,132 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=30000000 + +;######### CONTROL_THREAD CONFIG ############ +ControlThread.wait_for_flowgraph=false + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/archive/BDS3_datasets/long/20180713_211400_2.dat +SignalSource.item_type=ibyte +SignalSource.sampling_frequency=30000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.enable_throttle_control=false + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner +DataTypeAdapter.implementation=Ibyte_To_Complex +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.70 +InputFilter.band2_begin=0.80 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=30000000 +InputFilter.IF=1020000 +Resampler.implementation=Pass_Through +Resampler.sample_freq_in=30000000 +Resampler.sample_freq_out=30000000 +Resampler.item_type=gr_complex + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_B3.count=4 +Channels.in_acquisition=1 +Channel.signal=B3 + +Channel0.satellite = 29; +Channel1.satellite = 19; +Channel2.satellite = 20; +Channel3.satellite = 30; + + +;Channel0.satellite = 6; +;Channel1.satellite = 7; +;Channel2.satellite = 9; +;Channel3.satellite = 16; +;Channel4.satellite = 18; +;Channel5.satellite = 1; +;Channel6.satellite = 2; +;Channel7.satellite = 3; +;Channel8.satellite = 4; +;Channel9.satellite = 5; +;Channel10.satellite = 23; +;Channel11.satellite = 25; +;Channel12.satellite = 32; + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_B3.implementation=BEIDOU_B3I_PCPS_Acquisition +Acquisition_B3.item_type=gr_complex +Acquisition_B3.coherent_integration_time_ms=1 +Acquisition_B3.max_dwells = 1 +Acquisition_B3.pfa=0.01 +;Acquisition_B3.pfa=0.0000001; +Acquisition_B3.doppler_max=10000 +Acquisition_B3.doppler_step=50 +Acquisition_B3.dump=false +Acquisition_B3.dump_filename=./bds_acq +Acquisition_B3.blocking=false; +Acquisition_B3.bit_transition_flag = false; + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_B3.implementation=BEIDOU_B3I_DLL_PLL_Tracking +Tracking_B3.item_type=gr_complex +Tracking_B3.pll_bw_hz=25.0; +Tracking_B3.dll_bw_hz=2.50; +Tracking_B3.dump=false; +Tracking_B3.dump_filename=./epl_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_B3.implementation=BEIDOU_B3I_Telemetry_Decoder +TelemetryDecoder_B3.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=OFF ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=true diff --git a/conf/File_input/gnss-sdr_BDS_B3I_short.conf b/conf/File_input/gnss-sdr_BDS_B3I_short.conf new file mode 100644 index 000000000..a88c36092 --- /dev/null +++ b/conf/File_input/gnss-sdr_BDS_B3I_short.conf @@ -0,0 +1,81 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) +; 5C is the channel identifier for BeiDou B2a, both the data signal and the pilot signal + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=30000000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +;SignalSource.filename=/home/dmiralles/Documents/gnss-sdr/src/tests/signal_samples/USRP_BDS_B2a_201805171115_fs_25e6_if0e3_ishort_200ms.bin +SignalSource.filename=/archive/USRP_BDS_B3I_201805171118_fs_25e6_if0e3_ishort.bin +SignalSource.item_type=ishort +SignalSource.sampling_frequency=30000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=false + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner +InputFilter.implementation=Pass_Through +DataTypeAdapter.implementation=Ishort_To_Complex +Resampler.implementation=Direct_Resampler +Resampler.sample_freq_in=30000000 +Resampler.sample_freq_out=30000000 +Resampler.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channel.signal=B3 +Channels.in_acquisition=1 +Channels_B3.count=5; + +Channel0.satellite = 27; +Channel1.satellite = 22; +Channel2.satellite = 21; +Channel3.satellite = 28; +Channel4.satellite = 30; + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_B3.implementation=BEIDOU_B3I_PCPS_Acquisition +Acquisition_B3.item_type=gr_complex +Acquisition_B3.coherent_integration_time_ms = 1 +Acquisition_B3.max_dwells = 1 +Acquisition_B3.pfa=0.01 +Acquisition_B3.doppler_max=10000 +Acquisition_B3.doppler_step=50 +Acquisition_B3.dump=true +Acquisition_B3.dump_channel = 0; +Acquisition_B3.dump_filename=/archive/bds_b3i_acq +Acquisition_B3.blocking=false; +Acquisition_B3.bit_transition_flag = false; + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_B3.implementation= BEIDOU_B3I_DLL_PLL_Tracking; +Tracking_B3.item_type=gr_complex +Tracking_B3.early_late_space_chips=0.5 +Tracking_B3.pll_bw_hz=25.0; +Tracking_B3.dll_bw_hz=2.0; +Tracking_B3.dump=true; +Tracking_B3.dump_filename=/archive/bds_b3i_trk_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_B3.implementation=BEIDOU_B3I_Telemetry_Decoder +TelemetryDecoder_B3.dump=true +TelemetryDecoder_B3.dump_filename=/archive/bds_b3i_tel_dec.dat + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=true; +Observables.dump_filename=/archive/bds_b3i_observables.dat + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.averaging_depth=100 +PVT.flag_averaging=true +PVT.output_rate_ms=10 +PVT.display_rate_ms=500 diff --git a/conf/File_input/gnss-sdr_GLONASS_L1_CA_GPS_L1_CA_ibyte.conf b/conf/File_input/gnss-sdr_GLONASS_L1_CA_GPS_L1_CA_ibyte.conf new file mode 100644 index 000000000..021b12ae8 --- /dev/null +++ b/conf/File_input/gnss-sdr_GLONASS_L1_CA_GPS_L1_CA_ibyte.conf @@ -0,0 +1,142 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=6625000 +GNSS-SDR.num_sources=2 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource0.implementation=File_Signal_Source +SignalSource0.filename=../data/NT1065_L1_20160923_fs6625e6_if60e3_schar.bin ; <- PUT YOUR FILE HERE +SignalSource0.item_type=ibyte +SignalSource0.sampling_frequency=6625000 +SignalSource0.samples=0 +SignalSource0.dump=false; +SignalSource0.dump_filename=/archive/signal_glonass.bin + +SignalSource1.implementation=File_Signal_Source +SignalSource1.filename=../data/NT1065_GLONASS_L1_20160923_fs6625e6_if0e3_schar.bin ; <- PUT YOUR FILE HERE +SignalSource1.item_type=ibyte +SignalSource1.sampling_frequency=6625000 +SignalSource1.samples=0 +SignalSource1.dump=false; +SignalSource1.dump_filename=/archive/signal_glonass.bin + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner +DataTypeAdapter0.implementation=Ibyte_To_Complex +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.70 +InputFilter0.band2_begin=0.80 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=6625000 +InputFilter0.IF=60000 +Resampler0.implementation=Direct_Resampler +Resampler0.sample_freq_in=6625000 +Resampler0.sample_freq_out=6625000 +Resampler0.item_type=gr_complex + +SignalConditioner1.implementation=Signal_Conditioner +DataTypeAdapter1.implementation=Ibyte_To_Complex +InputFilter1.implementation=Pass_Through +InputFilter1.item_type=gr_complex +Resampler1.implementation=Pass_Through +Resampler1.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channels.in_acquisition=1 +Channels_1G.count=5 +Channels_1C.count=5 + +;# Defining GLONASS satellites +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +Channel4.RF_channel_ID=0 +Channel5.RF_channel_ID=1 +Channel6.RF_channel_ID=1 +Channel7.RF_channel_ID=1 +Channel8.RF_channel_ID=1 +Channel9.RF_channel_ID=1 + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.threshold=0.0 +Acquisition_1C.pfa=0.00001 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false; +Acquisition_1C.dump_filename=/archive/gps_acquisition.dat +;Acquisition_1C.coherent_integration_time_ms=10 + +Acquisition_1G.implementation=GLONASS_L1_CA_PCPS_Acquisition +Acquisition_1G.item_type=gr_complex +Acquisition_1G.threshold=0.0 +Acquisition_1G.pfa=0.00001 +Acquisition_1G.doppler_max=10000 +Acquisition_1G.doppler_step=250 +Acquisition_1G.dump=false; +Acquisition_1G.dump_filename=/archive/glo_acquisition.dat +;Acquisition_1G.coherent_integration_time_ms=10 + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.early_late_space_chips=0.5 +Tracking_1C.pll_bw_hz=20.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.dump=false; +Tracking_1C.dump_filename=/archive/gps_tracking_ch_ + +Tracking_1G.implementation=GLONASS_L1_CA_DLL_PLL_Tracking +Tracking_1G.item_type=gr_complex +Tracking_1G.early_late_space_chips=0.5 +Tracking_1G.pll_bw_hz=25.0; +Tracking_1G.dll_bw_hz=3.0; +Tracking_1G.dump=false; +Tracking_1G.dump_filename=/archive/glo_tracking_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1G.implementation=GLONASS_L1_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false; +Observables.dump_filename=/archive/gnss_observables.dat + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.trop_model=Saastamoinen +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.rtcm_tcp_port=2101 +PVT.rtcm_MT1019_rate_ms=5000 +PVT.rtcm_MT1045_rate_ms=5000 +PVT.rtcm_MT1097_rate_ms=1000 +PVT.rtcm_MT1077_rate_ms=1000 +PVT.rinex_version=2 diff --git a/conf/File_input/gnss-sdr_GLONASS_L1_CA_GPS_L2C_ibyte.conf b/conf/File_input/gnss-sdr_GLONASS_L1_CA_GPS_L2C_ibyte.conf new file mode 100644 index 000000000..8d37347c8 --- /dev/null +++ b/conf/File_input/gnss-sdr_GLONASS_L1_CA_GPS_L2C_ibyte.conf @@ -0,0 +1,143 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=6625000 +GNSS-SDR.num_sources=2 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource0.implementation=File_Signal_Source +SignalSource0.filename=/archive/NT1065_L2_20160923_fs6625e6_if60e3_schar.bin ; <- PUT YOUR FILE HERE +SignalSource0.item_type=ibyte +SignalSource0.sampling_frequency=6625000 +SignalSource0.samples=0 +SignalSource0.dump=false; +SignalSource0.dump_filename=/archive/signal_glonass.bin + +SignalSource1.implementation=File_Signal_Source +SignalSource1.filename=/archive/NT1065_GLONASS_L1_20160923_fs6625e6_if0e3_schar.bin ; <- PUT YOUR FILE HERE +SignalSource1.item_type=ibyte +SignalSource1.sampling_frequency=6625000 +SignalSource1.samples=0 +SignalSource1.dump=false; +SignalSource1.dump_filename=/archive/signal_glonass.bin + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner +DataTypeAdapter0.implementation=Ibyte_To_Complex +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.70 +InputFilter0.band2_begin=0.80 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=6625000 +InputFilter0.IF=60000 +Resampler0.implementation=Pass_Through +Resampler0.item_type=gr_complex + +SignalConditioner1.implementation=Signal_Conditioner +DataTypeAdapter1.implementation=Ibyte_To_Complex +InputFilter1.implementation=Pass_Through +InputFilter1.item_type=gr_complex +Resampler1.implementation=Pass_Through +Resampler1.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channels.in_acquisition=5 +Channels_2S.count=5 +Channels_1G.count=5 + +;# Defining GLONASS satellites +Channel0.RF_channel_ID=0 +Channel0.signal=2S +Channel1.RF_channel_ID=0 +Channel1.signal=2S +Channel2.RF_channel_ID=0 +Channel2.signal=2S +Channel3.RF_channel_ID=0 +Channel3.signal=2S +Channel4.RF_channel_ID=0 +Channel4.signal=2S +Channel5.RF_channel_ID=1 +Channel6.RF_channel_ID=1 +Channel7.RF_channel_ID=1 +Channel8.RF_channel_ID=1 +Channel9.RF_channel_ID=1 + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_2S.implementation=GPS_L2_M_PCPS_Acquisition +Acquisition_2S.item_type=gr_complex +Acquisition_2S.threshold=0.0 +Acquisition_2S.pfa=0.00001 +Acquisition_2S.doppler_max=10000 +Acquisition_2S.doppler_step=60 +Acquisition_2S.max_dwells=1 + +Acquisition_1G.implementation=GLONASS_L1_CA_PCPS_Acquisition +Acquisition_1G.item_type=gr_complex +Acquisition_1G.threshold=0.0 +Acquisition_1G.pfa=0.00001 +Acquisition_1G.doppler_max=10000 +Acquisition_1G.doppler_step=250 +Acquisition_1G.dump=false; +Acquisition_1G.dump_filename=/archive/glo_acquisition.dat + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_2S.implementation=GPS_L2_M_DLL_PLL_Tracking +Tracking_2S.item_type=gr_complex +Tracking_2S.early_late_space_chips=0.5 +Tracking_2S.pll_bw_hz=2.0; +Tracking_2S.dll_bw_hz=0.250; +Tracking_2S.order=2; +Tracking_2S.dump=false; +Tracking_2S.dump_filename=/archive/gps_tracking_ch_ + +Tracking_1G.implementation=GLONASS_L1_CA_DLL_PLL_Tracking +Tracking_1G.item_type=gr_complex +Tracking_1G.early_late_space_chips=0.5 +Tracking_1G.pll_bw_hz=25.0; +Tracking_1G.dll_bw_hz=3.0; +Tracking_1G.dump=false; +Tracking_1G.dump_filename=/archive/glo_tracking_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_2S.implementation=GPS_L2C_Telemetry_Decoder +TelemetryDecoder_1G.implementation=GLONASS_L1_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false; +Observables.dump_filename=/archive/gnss_observables.dat + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.trop_model=Saastamoinen +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.rtcm_tcp_port=2101 +PVT.rtcm_MT1019_rate_ms=5000 +PVT.rtcm_MT1045_rate_ms=5000 +PVT.rtcm_MT1097_rate_ms=1000 +PVT.rtcm_MT1077_rate_ms=1000 +PVT.rinex_version=3 diff --git a/conf/File_input/gnss-sdr_GLONASS_L1_CA_ibyte.conf b/conf/File_input/gnss-sdr_GLONASS_L1_CA_ibyte.conf new file mode 100644 index 000000000..46efcc5df --- /dev/null +++ b/conf/File_input/gnss-sdr_GLONASS_L1_CA_ibyte.conf @@ -0,0 +1,82 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=6625000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/media/dmiralles/Seagate Backup Plus Drive/GNSS Data/NT1065_GLONASS_L1_20160923_fs6625e6_if0e3_schar.bin ; <- PUT YOUR FILE HERE ; <- PUT YOUR FILE HERE +SignalSource.item_type=ibyte +SignalSource.sampling_frequency=6625000 +SignalSource.samples=0 +SignalSource.dump=false; +SignalSource.dump_filename=/archive/signal_glonass.bin + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner +DataTypeAdapter.implementation=Ibyte_To_Complex +InputFilter.implementation=Pass_Through +InputFilter.item_type=gr_complex +Resampler.implementation=Pass_Through +Resampler.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channel.signal=1G +Channels.in_acquisition=1 +Channels_1G.count=5 + +Channel0.satellite=24 ; k= +Channel1.satellite=1 ; k=1 +Channel2.satellite=2 ; k=-4 +Channel3.satellite=20 ; k=-5 +Channel4.satellite=21 ; k=4 + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1G.implementation=GLONASS_L1_CA_PCPS_Acquisition +Acquisition_1G.item_type=gr_complex +Acquisition_1G.threshold=0.0 +Acquisition_1G.pfa=0.0001 +Acquisition_1G.doppler_max=10000 +Acquisition_1G.doppler_step=250 +Acquisition_1G.dump=true; +Acquisition_1G.dump_filename=/archive/glo_acquisition.dat +;Acquisition_1G.coherent_integration_time_ms=1 +;Acquisition_1G.max_dwells = 5 + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1G.implementation=GLONASS_L1_CA_DLL_PLL_Tracking +Tracking_1G.item_type=gr_complex +Tracking_1G.early_late_space_chips=0.5 +Tracking_1G.pll_bw_hz=25.0; +Tracking_1G.dll_bw_hz=3.0; +Tracking_1G.dump=true; +Tracking_1G.dump_filename=/archive/glo_tracking_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1G.implementation=GLONASS_L1_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=true; +Observables.dump_filename=/archive/glo_observables.dat + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.trop_model=Saastamoinen +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.rtcm_tcp_port=2101 +PVT.rtcm_MT1019_rate_ms=5000 +PVT.rtcm_MT1045_rate_ms=5000 +PVT.rtcm_MT1097_rate_ms=1000 +PVT.rtcm_MT1077_rate_ms=1000 +PVT.rinex_version=2 diff --git a/conf/File_input/gnss-sdr_GLONASS_L1_CA_ibyte_coh_trk.conf b/conf/File_input/gnss-sdr_GLONASS_L1_CA_ibyte_coh_trk.conf new file mode 100644 index 000000000..bc48c28a7 --- /dev/null +++ b/conf/File_input/gnss-sdr_GLONASS_L1_CA_ibyte_coh_trk.conf @@ -0,0 +1,86 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=6625000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/archive/NT1065_GLONASS_L1_20160923_fs6625e6_if0e3_schar.bin ; <- PUT YOUR FILE HERE +SignalSource.item_type=ibyte +SignalSource.sampling_frequency=6625000 +SignalSource.samples=0 +SignalSource.dump=false; +SignalSource.dump_filename=/archive/signal_glonass.bin + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner +DataTypeAdapter.implementation=Ibyte_To_Complex +InputFilter.implementation=Pass_Through +InputFilter.item_type=gr_complex +Resampler.implementation=Pass_Through +Resampler.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channel.signal=1G +Channels.in_acquisition=2 +Channels_1G.count=8 + +;Channel0.satellite=24 ; k=2 +;Channel1.satellite=1 ; k=1 +;Channel2.satellite=2 ; k=-4 +;Channel3.satellite=20 ; k=-5 +;Channel4.satellite=21 ; k=4 + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1G.implementation=GLONASS_L1_CA_PCPS_Acquisition +Acquisition_1G.item_type=gr_complex +Acquisition_1G.threshold=0.0 +Acquisition_1G.pfa=0.0001 +Acquisition_1G.doppler_max=10000 +Acquisition_1G.doppler_step=250 +Acquisition_1G.dump=false; +Acquisition_1G.dump_filename=/archive/glo_acquisition.dat +;Acquisition_1G.coherent_integration_time_ms=1 +;Acquisition_1G.max_dwells = 5 + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1G.implementation=GLONASS_L1_CA_DLL_PLL_C_Aid_Tracking +Tracking_1G.item_type=gr_complex +Tracking_1G.early_late_space_chips=0.5 +Tracking_1G.pll_bw_hz=40.0; +Tracking_1G.dll_bw_hz=3.0; +Tracking_1G.pll_bw_narrow_hz = 25.0; +Tracking_1G.dll_bw_narrow_hz = 2.0; +Tracking_1G.extend_correlation_ms = 1; +Tracking_1G.dump=false; +Tracking_1G.dump_filename=/archive/glo_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1G.implementation=GLONASS_L1_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=/archive/glo_observables.dat + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.trop_model=Saastamoinen +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.rtcm_tcp_port=2101 +PVT.rtcm_MT1019_rate_ms=5000 +PVT.rtcm_MT1045_rate_ms=5000 +PVT.rtcm_MT1097_rate_ms=1000 +PVT.rtcm_MT1077_rate_ms=1000 +PVT.rinex_version=2 diff --git a/conf/File_input/gnss-sdr_GLONASS_L1_ibyte.conf b/conf/File_input/gnss-sdr_GLONASS_L1_ibyte.conf new file mode 100644 index 000000000..8f8baecfc --- /dev/null +++ b/conf/File_input/gnss-sdr_GLONASS_L1_ibyte.conf @@ -0,0 +1,101 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [Hz]. +GNSS-SDR.internal_fs_sps=6625000 + +;######### CONTROL_THREAD CONFIG ############ +ControlThread.wait_for_flowgraph=false + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/home/dmiralles/Documents/GSOC/GSOC2017/gnss-sdr/data/dmirallesNT1065_L2_20160831_fs6625e6_60e3_schar_1H.bin +SignalSource.item_type=ibyte +SignalSource.sampling_frequency=6625000 +SignalSource.freq=1602000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.sample_type=iq +SignalSource.seconds_to_skip=0 +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;DataTypeAdapter.implementation=Ishort_To_Complex +DataTypeAdapter.implementation=Ibyte_To_Complex +InputFilter.implementation=Pass_Through +;InputFilter.input_item_type=gr_complex +;InputFilter.output_item_type=gr_complex +InputFilter.item_type=gr_complex +;Resampler.implementation=Pass_Through +;Resampler.item_type=gr_complex +Resampler.implementation=Pass_Through +;Resampler.sample_freq_in=4000000 +;Resampler.sample_freq_out=2000000 +;Resampler.item_type=gr_complex +Resampler.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1R.count=8 ;Assuming here that identifier `1r=R` defines GLONASS SP signals +Channels.in_acquisition=1 +Channel.signal=1R +;Channel.item_type=cshort + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1R.dump=false +Acquisition_1R.dump_filename=./acq_dump.dat +Acquisition_1R.item_type=cshort +Acquisition_1R.sampled_ms=1 +Acquisition_1R.implementation=GLONASS_L1_CA_PCPS_Acquisition +Acquisition_1R.pfa=0.01 +;Acquisition_1C.pfa=0.000001 +Acquisition_1R.doppler_max=10000 +Acquisition_1R.doppler_step=250 +Acquisition_1R.tong_init_val=2 +Acquisition_1R.tong_max_val=10 +Acquisition_1R.tong_max_dwells=20 + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1R.implementation=GLONASS_L1_CA_DLL_PLL_C_Aid_Tracking +Tracking_1R.item_type=cshort +Tracking_1R.dump=false +Tracking_1R.dump_filename=../data/epl_tracking_ch_ +Tracking_1R.pll_bw_hz=40.0; +Tracking_1R.dll_bw_hz=4.0; +Tracking_1R.order=3; + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1R.implementation=GLONASS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1R.dump=false + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false diff --git a/conf/File_input/gnss-sdr_GLONASS_L2_CA_GPS_L1_CA_ibyte.conf b/conf/File_input/gnss-sdr_GLONASS_L2_CA_GPS_L1_CA_ibyte.conf new file mode 100644 index 000000000..abdbea4b2 --- /dev/null +++ b/conf/File_input/gnss-sdr_GLONASS_L2_CA_GPS_L1_CA_ibyte.conf @@ -0,0 +1,143 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=6625000 +GNSS-SDR.num_sources=2 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource0.implementation=File_Signal_Source +SignalSource0.filename=/media/dmiralles/Seagate Backup Plus Drive/GNSS Data/NT1065_L1_20160923_fs6625e6_if60e3_schar.bin ; <- PUT YOUR FILE HERE +SignalSource0.item_type=ibyte +SignalSource0.sampling_frequency=6625000 +SignalSource0.samples=0 +SignalSource0.dump=false; +SignalSource0.dump_filename=/archive/signal_glonass.bin + +SignalSource1.implementation=File_Signal_Source +SignalSource1.filename=/media/dmiralles/Seagate Backup Plus Drive/GNSS Data/NT1065_GLONASS_L2_20160923_fs6625e6_if0e3_schar.bin ; <- PUT YOUR FILE HERE +SignalSource1.item_type=ibyte +SignalSource1.sampling_frequency=6625000 +SignalSource1.samples=0 +SignalSource1.dump=false; +SignalSource1.dump_filename=/archive/signal_glonass.bin + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner +DataTypeAdapter0.implementation=Ibyte_To_Complex +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.70 +InputFilter0.band2_begin=0.80 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=6625000 +InputFilter0.IF=60000 +Resampler0.implementation=Direct_Resampler +Resampler0.sample_freq_in=6625000 +Resampler0.sample_freq_out=6625000 +Resampler0.item_type=gr_complex + +SignalConditioner1.implementation=Signal_Conditioner +DataTypeAdapter1.implementation=Ibyte_To_Complex +InputFilter1.implementation=Pass_Through +InputFilter1.item_type=gr_complex +Resampler1.implementation=Pass_Through +Resampler1.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channels.in_acquisition=1 +Channels_2G.count=5 +Channels_1C.count=5 + +;# Defining GLONASS satellites +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +Channel4.RF_channel_ID=0 +Channel5.RF_channel_ID=1 +Channel6.RF_channel_ID=1 +Channel7.RF_channel_ID=1 +Channel8.RF_channel_ID=1 +Channel9.RF_channel_ID=1 + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.threshold=0.0 +Acquisition_1C.pfa=0.00001 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false; +Acquisition_1C.dump_filename=/archive/gps_acquisition.dat +;Acquisition_1C.coherent_integration_time_ms=10 + +Acquisition_2G.implementation=GLONASS_L2_CA_PCPS_Acquisition +Acquisition_2G.item_type=gr_complex +Acquisition_2G.threshold=0.0 +Acquisition_2G.pfa=0.00001 +Acquisition_2G.doppler_max=10000 +Acquisition_2G.doppler_step=250 +Acquisition_2G.dump=false; +Acquisition_2G.dump_filename=/archive/glo_acquisition.dat +;Acquisition_2G.coherent_integration_time_ms=10 + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.early_late_space_chips=0.5 +Tracking_1C.pll_bw_hz=20.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.dump=false; +Tracking_1C.dump_filename=/archive/gps_tracking_ch_ + +Tracking_2G.implementation=GLONASS_L2_CA_DLL_PLL_Tracking +Tracking_2G.item_type=gr_complex +Tracking_2G.early_late_space_chips=0.5 +Tracking_2G.pll_bw_hz=25.0; +Tracking_2G.dll_bw_hz=2.0; +Tracking_2G.dump=false; +Tracking_2G.dump_filename=/archive/glo_tracking_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_2G.implementation=GLONASS_L2_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false; +Observables.dump_filename=/archive/gnss_observables.dat + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.trop_model=Saastamoinen +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.rtcm_tcp_port=2101 +PVT.rtcm_MT1019_rate_ms=5000 +PVT.rtcm_MT1045_rate_ms=5000 +PVT.rtcm_MT1097_rate_ms=1000 +PVT.rtcm_MT1077_rate_ms=1000 +PVT.rinex_version=2 diff --git a/conf/File_input/gnss-sdr_GLONASS_L2_CA_GPS_L2C_ibyte.conf b/conf/File_input/gnss-sdr_GLONASS_L2_CA_GPS_L2C_ibyte.conf new file mode 100644 index 000000000..79585a6ae --- /dev/null +++ b/conf/File_input/gnss-sdr_GLONASS_L2_CA_GPS_L2C_ibyte.conf @@ -0,0 +1,144 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=6625000 +GNSS-SDR.num_sources=2 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource0.implementation=File_Signal_Source +SignalSource0.filename=/archive/NT1065_L2_20160923_fs6625e6_if60e3_schar.bin ; <- PUT YOUR FILE HERE +SignalSource0.item_type=ibyte +SignalSource0.sampling_frequency=6625000 +SignalSource0.samples=0 +SignalSource0.dump=false; +SignalSource0.dump_filename=/archive/signal_glonass.bin + +SignalSource1.implementation=File_Signal_Source +SignalSource1.filename=/archive/NT1065_GLONASS_L2_20160923_fs6625e6_if0e3_schar.bin ; <- PUT YOUR FILE HERE +SignalSource1.item_type=ibyte +SignalSource1.sampling_frequency=6625000 +SignalSource1.samples=0 +SignalSource1.dump=false; +SignalSource1.dump_filename=/archive/signal_glonass.bin + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner +DataTypeAdapter0.implementation=Ibyte_To_Complex +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.70 +InputFilter0.band2_begin=0.80 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=6625000 +InputFilter0.IF=60000 +Resampler0.implementation=Pass_Through +Resampler0.item_type=gr_complex + +SignalConditioner1.implementation=Signal_Conditioner +DataTypeAdapter1.implementation=Ibyte_To_Complex +InputFilter1.implementation=Pass_Through +InputFilter1.item_type=gr_complex +Resampler1.implementation=Pass_Through +Resampler1.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channels.in_acquisition=5 +Channels_2S.count=5 +Channels_2G.count=5 + +;# Defining GLONASS satellites +Channel0.RF_channel_ID=0 +Channel0.signal=2S +Channel1.RF_channel_ID=0 +Channel1.signal=2S +Channel2.RF_channel_ID=0 +Channel2.signal=2S +Channel3.RF_channel_ID=0 +Channel3.signal=2S +Channel4.RF_channel_ID=0 +Channel4.signal=2S +Channel5.RF_channel_ID=1 +Channel6.RF_channel_ID=1 +Channel7.RF_channel_ID=1 +Channel8.RF_channel_ID=1 +Channel9.RF_channel_ID=1 + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_2S.implementation=GPS_L2_M_PCPS_Acquisition +Acquisition_2S.item_type=gr_complex +Acquisition_2S.threshold=0.0 +Acquisition_2S.pfa=0.00001 +Acquisition_2S.doppler_max=10000 +Acquisition_2S.doppler_step=60 +Acquisition_2S.max_dwells=1 + +Acquisition_2G.implementation=GLONASS_L2_CA_PCPS_Acquisition +Acquisition_2G.item_type=gr_complex +Acquisition_2G.threshold=0.0 +Acquisition_2G.pfa=0.00001 +Acquisition_2G.doppler_max=10000 +Acquisition_2G.doppler_step=250 +Acquisition_2G.dump=false; +Acquisition_2G.dump_filename=/archive/glo_acquisition.dat + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_2S.implementation=GPS_L2_M_DLL_PLL_Tracking +Tracking_2S.item_type=gr_complex +Tracking_2S.early_late_space_chips=0.5 +Tracking_2S.pll_bw_hz=2.0; +Tracking_2S.dll_bw_hz=0.250; +Tracking_2S.order=2; +Tracking_2S.dump=false; +Tracking_2S.dump_filename=/archive/gps_tracking_ch_ + +Tracking_2G.implementation=GLONASS_L2_CA_DLL_PLL_Tracking +Tracking_2G.item_type=gr_complex +Tracking_2G.early_late_space_chips=0.5 +Tracking_2G.pll_bw_hz=25.0; +Tracking_2G.dll_bw_hz=3.0; +Tracking_2G.dump=false; +Tracking_2G.dump_filename=/archive/glo_tracking_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_2S.implementation=GPS_L2C_Telemetry_Decoder +TelemetryDecoder_2G.implementation=GLONASS_L2_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false; +Observables.dump_filename=/archive/gnss_observables.dat + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.trop_model=Saastamoinen +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.rtcm_tcp_port=2101 +PVT.rtcm_MT1019_rate_ms=5000 +PVT.rtcm_MT1045_rate_ms=5000 +PVT.rtcm_MT1097_rate_ms=1000 +PVT.rtcm_MT1077_rate_ms=1000 +PVT.rinex_version=3 diff --git a/conf/File_input/gnss-sdr_GLONASS_L2_CA_ibyte.conf b/conf/File_input/gnss-sdr_GLONASS_L2_CA_ibyte.conf new file mode 100644 index 000000000..9ac3595eb --- /dev/null +++ b/conf/File_input/gnss-sdr_GLONASS_L2_CA_ibyte.conf @@ -0,0 +1,76 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=6625000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/media/dmiralles/Seagate Backup Plus Drive/GNSS Data/NT1065_GLONASS_L2_20160831_fs6625e6_60e3_schar_1m.bin ; <- PUT YOUR FILE HERE +SignalSource.item_type=ibyte +SignalSource.sampling_frequency=6625000 +SignalSource.samples=0 +SignalSource.dump=false; +SignalSource.dump_filename=/archive/signal_glonass.bin + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner +DataTypeAdapter.implementation=Ibyte_To_Complex +InputFilter.implementation=Pass_Through +InputFilter.item_type=gr_complex +Resampler.implementation=Pass_Through +Resampler.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channel.signal=2G +Channels.in_acquisition=1 +Channels_2G.count=5 + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_2G.implementation=GLONASS_L2_CA_PCPS_Acquisition +Acquisition_2G.item_type=gr_complex +Acquisition_2G.threshold=0.0 +Acquisition_2G.pfa=0.0001 +Acquisition_2G.doppler_max=10000 +Acquisition_2G.doppler_step=250 +Acquisition_2G.dump=true; +Acquisition_2G.dump_filename=/archive/glo_acquisition.dat +;Acquisition_2G.coherent_integration_time_ms=1 +;Acquisition_2G.max_dwells = 5 + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_2G.implementation=GLONASS_L2_CA_DLL_PLL_Tracking +Tracking_2G.item_type=gr_complex +Tracking_2G.early_late_space_chips=0.5 +Tracking_2G.pll_bw_hz=20.0; +Tracking_2G.dll_bw_hz=2.0; +Tracking_2G.dump=true; +Tracking_2G.dump_filename=/archive/glo_tracking_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_2G.implementation=GLONASS_L2_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=true; +Observables.dump_filename=/archive/glo_observables.dat + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.trop_model=Saastamoinen +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.rtcm_tcp_port=2101 +PVT.rtcm_MT1019_rate_ms=5000 +PVT.rtcm_MT1045_rate_ms=5000 +PVT.rtcm_MT1097_rate_ms=1000 +PVT.rtcm_MT1077_rate_ms=1000 +PVT.rinex_version=2 diff --git a/conf/File_input/gnss-sdr_GLONASS_L2_CA_ibyte_coh_trk.conf b/conf/File_input/gnss-sdr_GLONASS_L2_CA_ibyte_coh_trk.conf new file mode 100644 index 000000000..bc48c28a7 --- /dev/null +++ b/conf/File_input/gnss-sdr_GLONASS_L2_CA_ibyte_coh_trk.conf @@ -0,0 +1,86 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=6625000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/archive/NT1065_GLONASS_L1_20160923_fs6625e6_if0e3_schar.bin ; <- PUT YOUR FILE HERE +SignalSource.item_type=ibyte +SignalSource.sampling_frequency=6625000 +SignalSource.samples=0 +SignalSource.dump=false; +SignalSource.dump_filename=/archive/signal_glonass.bin + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner +DataTypeAdapter.implementation=Ibyte_To_Complex +InputFilter.implementation=Pass_Through +InputFilter.item_type=gr_complex +Resampler.implementation=Pass_Through +Resampler.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channel.signal=1G +Channels.in_acquisition=2 +Channels_1G.count=8 + +;Channel0.satellite=24 ; k=2 +;Channel1.satellite=1 ; k=1 +;Channel2.satellite=2 ; k=-4 +;Channel3.satellite=20 ; k=-5 +;Channel4.satellite=21 ; k=4 + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1G.implementation=GLONASS_L1_CA_PCPS_Acquisition +Acquisition_1G.item_type=gr_complex +Acquisition_1G.threshold=0.0 +Acquisition_1G.pfa=0.0001 +Acquisition_1G.doppler_max=10000 +Acquisition_1G.doppler_step=250 +Acquisition_1G.dump=false; +Acquisition_1G.dump_filename=/archive/glo_acquisition.dat +;Acquisition_1G.coherent_integration_time_ms=1 +;Acquisition_1G.max_dwells = 5 + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1G.implementation=GLONASS_L1_CA_DLL_PLL_C_Aid_Tracking +Tracking_1G.item_type=gr_complex +Tracking_1G.early_late_space_chips=0.5 +Tracking_1G.pll_bw_hz=40.0; +Tracking_1G.dll_bw_hz=3.0; +Tracking_1G.pll_bw_narrow_hz = 25.0; +Tracking_1G.dll_bw_narrow_hz = 2.0; +Tracking_1G.extend_correlation_ms = 1; +Tracking_1G.dump=false; +Tracking_1G.dump_filename=/archive/glo_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1G.implementation=GLONASS_L1_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=/archive/glo_observables.dat + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.trop_model=Saastamoinen +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.rtcm_tcp_port=2101 +PVT.rtcm_MT1019_rate_ms=5000 +PVT.rtcm_MT1045_rate_ms=5000 +PVT.rtcm_MT1097_rate_ms=1000 +PVT.rtcm_MT1077_rate_ms=1000 +PVT.rinex_version=2 diff --git a/conf/File_input/gnss-sdr_GPS_L1_CA_ibyte.conf b/conf/File_input/gnss-sdr_GPS_L1_CA_ibyte.conf new file mode 100644 index 000000000..6afe08ced --- /dev/null +++ b/conf/File_input/gnss-sdr_GPS_L1_CA_ibyte.conf @@ -0,0 +1,94 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=6625000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/archive/NT1065_L1_20160923_fs6625e6_if60e3_schar.bin ; <- PUT YOUR FILE HERE +SignalSource.item_type=ibyte +;SignalSource.samples=66250000 +SignalSource.samples=0 +SignalSource.dump=false; + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner +DataTypeAdapter.implementation=Ibyte_To_Complex +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.70 +InputFilter.band2_begin=0.80 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=6625000 +InputFilter.IF=60000 +Resampler.implementation=Direct_Resampler +Resampler.sample_freq_in=6625000 +Resampler.sample_freq_out=6625000 +Resampler.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channel.signal=1C +Channels.in_acquisition=1 +Channels_1C.count=6 + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.threshold=0.01 +;Acquisition_1C.pfa=0.00001 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false; +Acquisition_1C.dump_filename=/archive/gps_acquisition.dat +;Acquisition_1C.coherent_integration_time_ms=10 + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.early_late_space_chips=0.5 +Tracking_1C.pll_bw_hz=25.0; +Tracking_1C.dll_bw_hz=3.0; +Tracking_1C.dump=false; +Tracking_1C.dump_filename=/archive/gps_tracking_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=true; +Observables.dump_filename=/archive/gps_observables.dat + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.trop_model=Saastamoinen +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.rtcm_tcp_port=2101 +PVT.rtcm_MT1019_rate_ms=5000 +PVT.rtcm_MT1045_rate_ms=5000 +PVT.rtcm_MT1097_rate_ms=1000 +PVT.rtcm_MT1077_rate_ms=1000 +PVT.rinex_version=3 diff --git a/conf/File_input/gnss-sdr_GPS_L1_SPIR.conf b/conf/File_input/gnss-sdr_GPS_L1_SPIR.conf new file mode 100644 index 000000000..d83bd63d3 --- /dev/null +++ b/conf/File_input/gnss-sdr_GPS_L1_SPIR.conf @@ -0,0 +1,137 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 + + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Spir_File_Signal_Source +SignalSource.filename=/dtalogger/signals/spir/data/20Secs/20Secs_L1.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=int +SignalSource.sampling_frequency=80000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through +DataTypeAdapter.item_type=float + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat +InputFilter.input_item_type=float +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=80000000 +InputFilter.IF=10164 +InputFilter.decimation_factor=20 + + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.item_type=gr_complex +Resampler.sample_freq_in=80000000 +Resampler.sample_freq_out=4000000 +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=10 +Channels_1B.count=0 +Channels.in_acquisition=1 + +Channel.signal=1C + + +;######### CHANNEL 0 CONFIG ############ +;Channel0.satellite=20 + +;######### CHANNEL 1 CONFIG ############ +;Channel1.satellite=12 + +;######### CHANNEL 2 CONFIG ############ +;Channel2.satellite=11 + +;######### CHANNEL 3 CONFIG ############ +;Channel3.satellite=19 + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition_Fine_Doppler +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=0.005 +;Acquisition_1C.pfa=0.0001 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_min=-10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.max_dwells=5 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=20.0; +Tracking_1C.order=3; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +;#implementation: +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +;#implementation: Position Velocity and Time (PVT) implementation algorithm +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=500 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=true; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_GPS_L1_acq_QuickSync.conf b/conf/File_input/gnss-sdr_GPS_L1_acq_QuickSync.conf new file mode 100644 index 000000000..356dde132 --- /dev/null +++ b/conf/File_input/gnss-sdr_GPS_L1_acq_QuickSync.conf @@ -0,0 +1,108 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 + + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/datalogger/signals/CTTC/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=ishort +SignalSource.sampling_frequency=4000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Ishort_To_Complex +DataTypeAdapter.dump=false +DataTypeAdapter.dump_filename=../data/data_type_adapter.dat + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Pass_Through +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.item_type=gr_complex +Resampler.sample_freq_in=4000000 +Resampler.sample_freq_out=4000000 +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=5 +Channels.in_acquisition=1 + + +;######### ACQUISITION GLOBAL CONFIG ############_1C +Acquisition_1C.implementation=GPS_L1_CA_PCPS_QuickSync_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent-integration_time_ms=4 +Acquisition_1C.dump=true +;Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### ACQUISITION CHANNELS CONFIG ###### +Acquisition_1C.implementation=GPS_L1_CA_PCPS_QuickSync_Acquisition +Acquisition_1C.threshold=0.4 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=50.0; +Tracking_1C.dll_bw_hz=4.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5 +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100; +PVT.display_rate_ms=500; +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea +PVT.flag_nmea_tty_port=true +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_GPS_L1_gr_complex.conf b/conf/File_input/gnss-sdr_GPS_L1_gr_complex.conf new file mode 100644 index 000000000..84179dbed --- /dev/null +++ b/conf/File_input/gnss-sdr_GPS_L1_gr_complex.conf @@ -0,0 +1,98 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf + + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 + + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/datalogger/signals/CTTC/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=ishort +SignalSource.sampling_frequency=4000000 +SignalSource.freq=1575420000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +DataTypeAdapter.implementation=Ishort_To_Complex +DataTypeAdapter.dump=false +DataTypeAdapter.dump_filename=../data/DataTypeAdapter.dat + +InputFilter.implementation=Pass_Through +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex + +Resampler.implementation=Pass_Through +Resampler.item_type=gr_complex + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=5 +Channels.in_acquisition=1 +Channel.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +;Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.dump=true +Tracking_1C.dump_filename=epl_tracking_ch_ +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=4.0; +Tracking_1C.order=3; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_c + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=1 +PVT.display_rate_ms=100 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false diff --git a/conf/File_input/gnss-sdr_GPS_L1_ishort.conf b/conf/File_input/gnss-sdr_GPS_L1_ishort.conf new file mode 100644 index 000000000..1d76c2a2f --- /dev/null +++ b/conf/File_input/gnss-sdr_GPS_L1_ishort.conf @@ -0,0 +1,102 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2000000 + +;######### CONTROL_THREAD CONFIG ############ +ControlThread.wait_for_flowgraph=false + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/archive/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=ishort +SignalSource.sampling_frequency=4000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Ishort_To_Complex + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Pass_Through +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Direct_Resampler +Resampler.sample_freq_in=4000000 +Resampler.sample_freq_out=2000000 +Resampler.item_type=gr_complex + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels.in_acquisition=1 +Channel.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +;Acquisition_1C.pfa=0.000001 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat +Acquisition_1C.blocking=false; + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=4.0; +Tracking_1C.order=3; +Tracking_1C.dump=false; +Tracking_1C.dump_filename=./epl_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=true +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false diff --git a/conf/File_input/gnss-sdr_Galileo_E1_acq_QuickSync.conf b/conf/File_input/gnss-sdr_Galileo_E1_acq_QuickSync.conf new file mode 100644 index 000000000..3f3a9831e --- /dev/null +++ b/conf/File_input/gnss-sdr_Galileo_E1_acq_QuickSync.conf @@ -0,0 +1,100 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 + + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/datalogger/signals/CTTC/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=ishort +SignalSource.sampling_frequency=4000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Ishort_To_Complex +DataTypeAdapter.dump=false +DataTypeAdapter.dump_filename=../data/data_type_adapter.dat + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Pass_Through + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat +Resampler.item_type=gr_complex + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1B.count=4 +Channels.in_acquisition=1 +Channel.signal=1B + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_QuickSync_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +Acquisition_1B.threshold=0.05 +Acquisition_1B.doppler_max=15000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.coherent_integration_time_ms=8 +Acquisition_1B.cboc=false +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=20.0; +Tracking_1B.dll_bw_hz=2.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + +;######### TELEMETRY DECODER CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100; +PVT.display_rate_ms=500; +PVT.dump=false +PVT.dump_filename=./PVT +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=true; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false; +PVT.flag_rtcm_tty_port=false; +PVT.rtcm_dump_devname=/dev/pts/1 diff --git a/conf/File_input/gnss-sdr_Galileo_E1_ishort.conf b/conf/File_input/gnss-sdr_Galileo_E1_ishort.conf new file mode 100644 index 000000000..257bd9091 --- /dev/null +++ b/conf/File_input/gnss-sdr_Galileo_E1_ishort.conf @@ -0,0 +1,109 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 + + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/datalogger/signals/CTTC/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=ishort +SignalSource.sampling_frequency=4000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=true + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Ishort_To_Complex + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Pass_Through +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.item_type=gr_complex +Resampler.sample_freq_in=4000000 +Resampler.sample_freq_out=4000000 +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1B.count=8 +Channels.in_acquisition=1 +Channel.signal=1B + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +;Acquisition_1B.threshold=0 +Acquisition_1B.pfa=0.00001 +Acquisition_1B.doppler_max=15000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.cboc=false +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat +Acquisition_1B.blocking=false + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.dump=true +Tracking_1B.dump_filename=./veml_tracking_ch_ +Tracking_1B.pll_bw_hz=20.0; +Tracking_1B.dll_bw_hz=3.0; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.track_pilot=true +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### TELEMETRY DECODER CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100; +PVT.display_rate_ms=500; +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=true +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=true; +PVT.rtcm_tcp_port=2101 +PVT.rtcm_MT1045_rate_ms=5000 +PVT.rtcm_MSM_rate_ms=1000 +PVT.flag_rtcm_tty_port=false; +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_Galileo_E1_nsr.conf b/conf/File_input/gnss-sdr_Galileo_E1_nsr.conf new file mode 100644 index 000000000..883927c8e --- /dev/null +++ b/conf/File_input/gnss-sdr_Galileo_E1_nsr.conf @@ -0,0 +1,127 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +;GNSS-SDR.internal_fs_sps=6826700 +GNSS-SDR.internal_fs_sps=2560000 +;GNSS-SDR.internal_fs_sps=4096000 +;GNSS-SDR.internal_fs_sps=5120000 + + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Nsr_File_Signal_Source +SignalSource.filename=/datalogger/signals/ifen/E1L1_FE0_Band0.stream ; <- PUT YOUR FILE HERE +SignalSource.item_type=byte +SignalSource.sampling_frequency=20480000 +SignalSource.samples=0 ; 0 means the entire file +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through +DataTypeAdapter.item_type=float + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.input_item_type=float +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 + +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 + +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 + +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=20480000 +InputFilter.IF=5499998.47412109 +InputFilter.decimation_factor=8 +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1B.count=8 +Channels.in_acquisition=1 +Channel.signal=1B + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +Acquisition_1B.pfa=0.0000008 +Acquisition_1B.doppler_max=15000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.cboc=false ; This option allows you to choose between acquiring with CBOC signal [true] or sinboc(1,1) signal [false]. Use only if GNSS-SDR.internal_fs_sps is greater than or equal to 6138000 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=20.0; +Tracking_1B.dll_bw_hz=2.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### TELEMETRY DECODER CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=true +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump=true +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea +PVT.flag_nmea_tty_port=true +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 diff --git a/conf/File_input/gnss-sdr_Galileo_E5a.conf b/conf/File_input/gnss-sdr_Galileo_E5a.conf new file mode 100644 index 000000000..7ac27534e --- /dev/null +++ b/conf/File_input/gnss-sdr_Galileo_E5a.conf @@ -0,0 +1,121 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=32000000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +;GNSS-SDR.SUPL_gps_enabled=false +;GNSS-SDR.SUPL_read_gps_assistance_xml=false +;GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +;GNSS-SDR.SUPL_gps_ephemeris_port=7275 +;GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +;GNSS-SDR.SUPL_gps_acquisition_port=7275 +;GNSS-SDR.SUPL_MCC=244 +;GNSS-SDR.SUPL_MNC=5 +;GNSS-SDR.SUPL_LAC=0x59e2 +;GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/datalogger/signals/ifen/32MS_complex.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=gr_complex +SignalSource.sampling_frequency=32000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Pass_Through + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_5X.count=1 +Channels.in_acquisition=1 + +;######### SPECIFIC CHANNELS CONFIG ###### +;#The following options are specific to each channel and overwrite the generic options + +;######### CHANNEL 0 CONFIG ############ +;Channel0.satellite=19 + +;######### CHANNEL 1 CONFIG ############ +;Channel1.satellite=12 + +;######### CHANNEL 2 CONFIG ############ +;Channel2.satellite=11 + +;######### CHANNEL 3 CONFIG ############ + +;Channel3.system=Galileo +;Channel3.signal=5Q +;Channel3.satellite=20 + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_5X.implementation=Galileo_E5a_Noncoherent_IQ_Acquisition_CAF +Acquisition_5X.item_type=gr_complex +Acquisition_5X.coherent_integration_time_ms=1 +Acquisition_5X.pfa=0.01 +Acquisition_5X.pfa=0.0003 +Acquisition_5X.doppler_max=10000 +Acquisition_5X.doppler_step=250 +Acquisition_5X.bit_transition_flag=false +Acquisition_5X.max_dwells=1 +Acquisition_5X.CAF_window_hz=0 +Acquisition_5X.Zero_padding=0 +Acquisition_5X.dump=false +Acquisition_5X.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_5X.implementation=Galileo_E5a_DLL_PLL_Tracking +Tracking_5X.item_type=gr_complex +Tracking_5X.pll_bw_hz=20.0; +Tracking_5X.dll_bw_hz=20.0; +Tracking_5X.pll_bw_narrow_hz=2.0; +Tracking_5X.dll_bw_narrow_hz=5.0; +Tracking_5X.order=2; +Tracking_5X.early_late_space_chips=0.5; +Tracking_5X.dump=false +Tracking_5X.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER CONFIG ############ +TelemetryDecoder_5X.implementation=Galileo_E5a_Telemetry_Decoder +TelemetryDecoder_5X.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=true; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_Galileo_E5a_IFEN_CTTC.conf b/conf/File_input/gnss-sdr_Galileo_E5a_IFEN_CTTC.conf new file mode 100644 index 000000000..9c2ea55cc --- /dev/null +++ b/conf/File_input/gnss-sdr_Galileo_E5a_IFEN_CTTC.conf @@ -0,0 +1,157 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=50000000 + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +;GNSS-SDR.SUPL_gps_enabled=false +;GNSS-SDR.SUPL_read_gps_assistance_xml=false +;GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +;GNSS-SDR.SUPL_gps_ephemeris_port=7275 +;GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +;GNSS-SDR.SUPL_gps_acquisition_port=7275 +;GNSS-SDR.SUPL_MCC=244 +;GNSS-SDR.SUPL_MNC=5 +;GNSS-SDR.SUPL_LAC=0x59e2 +;GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/datalogger/signals/ifen/Galileo_E5ab_IFEN_CTTC_run1.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=gr_complex +SignalSource.sampling_frequency=50000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=50000000 +InputFilter.IF=-15345000 +InputFilter.decimation_factor=1 +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_5X.count=8 +Channels.in_acquisition=1 +Channel.signal=5X + +;######### SPECIFIC CHANNELS CONFIG ###### +;#The following options are specific to each channel and overwrite the generic options + +;######### CHANNEL 0 CONFIG ############ +Channel0.signal=5X +;Channel0.satellite=19 +;Channel0.repeat_satellite=true + +;######### CHANNEL 1 CONFIG ############ +Channel1.signal=5X +;Channel1.satellite=12 + +;######### CHANNEL 2 CONFIG ############ +Channel2.signal=5X +;Channel2.satellite=11 + +;######### CHANNEL 3 CONFIG ############ +Channel3.signal=5X +;Channel3.satellite=20 + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_5X.implementation=Galileo_E5a_Noncoherent_IQ_Acquisition_CAF +Acquisition_5X.item_type=gr_complex +Acquisition_5X.coherent_integration_time_ms=1 +Acquisition_5X.threshold=0.002 +Acquisition_5X.doppler_max=10000 +Acquisition_5X.doppler_step=250 +Acquisition_5X.bit_transition_flag=false +Acquisition_5X.max_dwells=1 +Acquisition_5X.CAF_window_hz=0 ; **Only for E5a** Resolves doppler ambiguity averaging the specified BW in the winner code delay. If set to 0 CAF filter is desactivated. Recommended value 3000 Hz +Acquisition_5X.Zero_padding=0 ; **Only for E5a** Avoids power loss and doppler ambiguity in bit transitions by correlating one code with twice the input data length, ensuring that at least one full code is present without transitions. If set to 1 it is ON, if set to 0 it is OFF. +Acquisition_5X.dump=false +Acquisition_5X.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_5X.implementation=Galileo_E5a_DLL_PLL_Tracking +Tracking_5X.item_type=gr_complex +Tracking_5X.pll_bw_hz=20.0; +Tracking_5X.dll_bw_hz=20.0; +Tracking_5X.pll_bw_narrow_hz=20.0; +Tracking_5X.dll_bw_narrow_hz=20.0; +Tracking_5X.order=2; +Tracking_5X.early_late_space_chips=0.5; +Tracking_5X.dump=false +Tracking_5X.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER CONFIG ############ +TelemetryDecoder_5X.implementation=Galileo_E5a_Telemetry_Decoder +TelemetryDecoder_5X.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=OFF ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=OFF ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.dump=false +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea +PVT.flag_nmea_tty_port=true +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 diff --git a/conf/File_input/gnss-sdr_Hybrid_byte.conf b/conf/File_input/gnss-sdr_Hybrid_byte.conf new file mode 100644 index 000000000..3daee47ce --- /dev/null +++ b/conf/File_input/gnss-sdr_Hybrid_byte.conf @@ -0,0 +1,160 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=20000000 + + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/media/javier/Extreme 500/fraunhofer/L125_III1b_210s_L1.bin ; <- PUT YOUR FILE HERE +SignalSource.item_type=byte +SignalSource.sampling_frequency=20000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Ibyte_To_Complex + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Pass_Through +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.item_type=gr_complex +Resampler.sample_freq_in=20000000 +Resampler.sample_freq_out=20000000 +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=10 +Channels_1B.count=10 +Channels.in_acquisition=1 + +;#signal: +;# "1C" GPS L1 C/A +;# "1B" GALILEO E1 B (I/NAV OS/CS/SoL) +;# "1G" GLONASS L1 C/A +;# "2S" GPS L2 L2C (M) +;# "5X" GALILEO E5a I+Q +;# "L5" GPS L5 + +;#if the option is disabled by default is assigned "1C" GPS L1 C/A +Channel0.signal=1C +Channel1.signal=1C +Channel2.signal=1C +Channel3.signal=1C +Channel4.signal=1C +Channel5.signal=1C +Channel6.signal=1C +Channel7.signal=1C +Channel8.signal=1B +Channel9.signal=1B +Channel10.signal=1B +Channel11.signal=1B +Channel12.signal=1B +Channel13.signal=1B +Channel14.signal=1B +Channel15.signal=1B +Channel16.signal=1B +Channel17.signal=1B +Channel18.signal=1B +Channel19.signal=1B + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.threshold=3.5 +Acquisition_1C.blocking=true +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### GALILEO ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.threshold=2.5 +Acquisition_1B.blocking=true +Acquisition_1B.doppler_max=5000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.extend_correlation_ms=1 +Tracking_1C.pll_bw_hz=40; +Tracking_1C.pll_bw_narrow_hz=30; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.dll_bw_narrow_hz=1.5; +Tracking_1C.order=2; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TRACKING GALILEO CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=15.0; +Tracking_1B.dll_bw_hz=3.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### TELEMETRY DECODER GALILEO CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### OBSERVABLES CONFIG ############ +;#implementation: +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=10; +PVT.display_rate_ms=500; +PVT.elevation_mask=15; +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_Hybrid_byte_sim.conf b/conf/File_input/gnss-sdr_Hybrid_byte_sim.conf new file mode 100644 index 000000000..b92bdc4a9 --- /dev/null +++ b/conf/File_input/gnss-sdr_Hybrid_byte_sim.conf @@ -0,0 +1,145 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2600000 + + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/Users/carlesfernandez/git/cttc/build/signal_out.bin ; <- PUT YOUR FILE HERE +SignalSource.item_type=byte +SignalSource.sampling_frequency=4000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Ibyte_To_Complex +DataTypeAdapter.dump=false +DataTypeAdapter.dump_filename=../data/DataTypeAdapter.dat + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Pass_Through +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.item_type = gr_complex; + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=11 +Channels_1B.count=0 +Channels.in_acquisition=1 + +;#signal: +Channel1.signal=1C +Channel2.signal=1C +Channel3.signal=1C +Channel4.signal=1C +Channel5.signal=1C +Channel6.signal=1C +Channel7.signal=1C +Channel8.signal=1C +Channel9.signal=1C +Channel10.signal=1C +Channel11.signal=1C +Channel12.signal=1C +Channel13.signal=1B +Channel14.signal=1B +Channel15.signal=1B + + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=2.5 +;Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=6000 +Acquisition_1C.doppler_step=100 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### GALILEO ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +;Acquisition_1B.threshold=0 +Acquisition_1B.pfa=0.0000008 +Acquisition_1B.doppler_max=15000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=20.0; +Tracking_1C.dll_bw_hz=1.5; +Tracking_1C.order=3; + + +;######### TRACKING GALILEO CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ +Tracking_1B.pll_bw_hz=15.0; +Tracking_1B.dll_bw_hz=2.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### TELEMETRY DECODER GALILEO CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100; +PVT.display_rate_ms=500; +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_Hybrid_gr_complex.conf b/conf/File_input/gnss-sdr_Hybrid_gr_complex.conf new file mode 100644 index 000000000..b375cec21 --- /dev/null +++ b/conf/File_input/gnss-sdr_Hybrid_gr_complex.conf @@ -0,0 +1,131 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4092000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/datalogger/signals/sim/GPS_sim1.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=gr_complex +SignalSource.sampling_frequency=4092000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Pass_Through + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=1 +Channels_1B.count=0 +Channels.in_acquisition=1 + +;#if the option is disabled by default is assigned "1C" GPS L1 C/A +Channel0.signal=1C +Channel1.signal=1B +Channel2.signal=1B +Channel3.signal=1B +Channel4.signal=1B +Channel5.signal=1B +Channel6.signal=1B +Channel7.signal=1B +Channel8.signal=1B +Channel9.signal=1B +Channel10.signal=1B +Channel11.signal=1B +Channel12.signal=1B +Channel13.signal=1B +Channel14.signal=1B +Channel15.signal=1B + + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=2.5 +;Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=100 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### GALILEO ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +;Acquisition_1B.threshold=0 +Acquisition_1B.pfa=0.0000002 +Acquisition_1B.doppler_max=15000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.extend_correlation_ms=10 +Tracking_1C.pll_bw_hz=40; +Tracking_1C.pll_bw_narrow_hz=25; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.dll_bw_narrow_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.dump=true +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TRACKING GALILEO CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=15.0; +Tracking_1B.dll_bw_hz=2.0; +Tracking_1B.fll_bw_hz=10.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### TELEMETRY DECODER GALILEO CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=10; +PVT.display_rate_ms=500; +PVT.dump=false +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_Hybrid_ishort.conf b/conf/File_input/gnss-sdr_Hybrid_ishort.conf new file mode 100644 index 000000000..3931754e0 --- /dev/null +++ b/conf/File_input/gnss-sdr_Hybrid_ishort.conf @@ -0,0 +1,161 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + + +;######### SIGNAL_SOURCE CONFIG ############ +;#implementation +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/datalogger/signals/CTTC/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=ishort +SignalSource.sampling_frequency=4000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Ishort_To_Complex + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Pass_Through +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.item_type=gr_complex +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=0 +Channels_1B.count=5 +Channels.in_acquisition=1 + +;#signal: +;# "1C" GPS L1 C/A +;# "2S" GPS L2 L2C (M) +;# "1B" GALILEO E1 B (I/NAV OS/CS/SoL) +;# "5X" GALILEO E5a I+Q +Channel0.signal=1B +Channel1.signal=1B +Channel2.signal=1B +Channel3.signal=1B +Channel4.signal=1B +Channel5.signal=1B +Channel6.signal=1B +Channel7.signal=1B + + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.015 +;Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### GALILEO ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +;Acquisition_1B.threshold=0 +Acquisition_1B.pfa=0.0000008; 0.0000008 +Acquisition_1B.doppler_max=15000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.cboc=false; +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=50.0; +Tracking_1C.dll_bw_hz=5.0; +Tracking_1C.order=3; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TRACKING GALILEO CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=20.0; +Tracking_1B.dll_bw_hz=2.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### TELEMETRY DECODER GALILEO CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100; +PVT.display_rate_ms=500; +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.rtcm_tcp_port=2101 +PVT.rtcm_MT1045_rate_ms=5000 ; Period (in ms) of Galileo ephemeris messages. 0 mutes this message +PVT.rtcm_MT1045_rate_ms=5000 ; Period (in ms) of GPS ephemeris messages. 0 mutes this message +PVT.rtcm_MT1097_rate_ms=1000 ; Period (in ms) of Galileo observables. 0 mutes this message +PVT.rtcm_MT1077_rate_ms=1000 ; Period (in ms) of GPS observables. 0 mutes this message +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_galileo_E1_extended_correlator_byte.conf b/conf/File_input/gnss-sdr_galileo_E1_extended_correlator_byte.conf new file mode 100644 index 000000000..a0715fba8 --- /dev/null +++ b/conf/File_input/gnss-sdr_galileo_E1_extended_correlator_byte.conf @@ -0,0 +1,141 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=20000000 + + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/media/javier/SISTEMA/signals/fraunhofer/L125_III1b_210s_L1.bin ; <- PUT YOUR FILE HERE +SignalSource.item_type=byte +SignalSource.sampling_frequency=20000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Ibyte_To_Complex + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Pass_Through + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=0 +Channels_1B.count=8 + +Channels.in_acquisition=1 + +Channel1.signal=1B +Channel2.signal=1B +Channel3.signal=1B +Channel4.signal=1B +Channel5.signal=1B +Channel6.signal=1B +Channel7.signal=1B +Channel8.signal=1B +Channel9.signal=1B +Channel10.signal=1B +Channel11.signal=1B +Channel12.signal=1B +Channel13.signal=1B +Channel14.signal=1B +Channel15.signal=1B + + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.scoherent_integration_time_ms=1 +Acquisition_1C.threshold=2.5 +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### GALILEO ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +Acquisition_1B.acquire_pilot=true +Acquisition_1B.threshold=2.5 +Acquisition_1B.doppler_max=5000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.bit_transition_flag=true +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=../data/acq_dump.dat + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=30.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TRACKING GALILEO CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.track_pilot=true +Tracking_1B.pll_bw_hz=4.0; +Tracking_1B.dll_bw_hz=0.5; +Tracking_1B.pll_bw_narrow_hz=2.0; +Tracking_1B.dll_bw_narrow_hz=0.25; +Tracking_1B.extend_correlation_symbols=4; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.early_late_space_narrow_chips=0.06; +Tracking_1B.very_early_late_space_narrow_chips=0.25; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + +;######### TELEMETRY DECODER GALILEO CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100; +PVT.display_rate_ms=500; +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_galileo_E1_extended_correlator_labsat.conf b/conf/File_input/gnss-sdr_galileo_E1_extended_correlator_labsat.conf new file mode 100644 index 000000000..91387a875 --- /dev/null +++ b/conf/File_input/gnss-sdr_galileo_E1_extended_correlator_labsat.conf @@ -0,0 +1,169 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=5456000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Labsat_Signal_Source +SignalSource.selected_channel=1 +;#filename: path to file with the captured GNSS signal samples to be processed +;# Labsat sile source automatically increments the file name when the signal is split in several files +;# the adapter adds "_0000.LS3" to this base path and filename. Next file will be "_0001.LS3" and so on +;# in this example, the first file complete path will be ../signals/GPS_025_0000.LS3 +SignalSource.filename=../signals/GPS_025 ; <- PUT YOUR FILE HERE +SignalSource.item_type=gr_complex +SignalSource.sampling_frequency=16368000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through +DataTypeAdapter.item_type=gr_complex + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 + +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 + +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 + +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 + +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=16368000 +InputFilter.IF=0 +InputFilter.decimation_factor=3 + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=0 +Channels_1B.count=6 +Channels.in_acquisition=1 + +Channel0.signal=1B +Channel1.signal=1B +Channel2.signal=1B +Channel3.signal=1B +Channel4.signal=1B +Channel5.signal=1B +Channel6.signal=1B +Channel7.signal=1B +Channel8.signal=1B +Channel9.signal=1B +Channel10.signal=1B +Channel11.signal=1B +Channel12.signal=1B +Channel13.signal=1B +Channel14.signal=1B +Channel15.signal=1B + + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=2.5 +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + +;######### GALILEO ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +Acquisition_1B.acquire_pilot=true +Acquisition_1B.threshold=2.5 +Acquisition_1B.doppler_max=5000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.bit_transition_flag=true +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=../data/acq_dump.dat + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + +;######### TRACKING GALILEO CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.track_pilot=true +Tracking_1B.pll_bw_hz=7.5; +Tracking_1B.dll_bw_hz=0.5; +Tracking_1B.pll_bw_narrow_hz=2.5; +Tracking_1B.dll_bw_narrow_hz=0.25; +Tracking_1B.extend_correlation_symbols=4; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.early_late_space_narrow_chips=0.15; +Tracking_1B.very_early_late_space_narrow_chips=0.30; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + +;######### TELEMETRY DECODER GALILEO CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100; +PVT.display_rate_ms=500; +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_labsat_kf.conf b/conf/File_input/gnss-sdr_labsat_kf.conf new file mode 100644 index 000000000..31787abab --- /dev/null +++ b/conf/File_input/gnss-sdr_labsat_kf.conf @@ -0,0 +1,185 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2021 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=5456000 +GNSS-SDR.use_acquisition_resampler=true + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Labsat_Signal_Source +SignalSource.selected_channel=1 +;#filename: path to file with the captured GNSS signal samples to be processed +;# Labsat sile source automatically increments the file name when the signal is split in several files +;# the adapter adds "_0000.LS3" to this base path and filename. Next file will be "_0001.LS3" and so on +;# in this example, the first file complete path will be ../signals/GPS_025_ +SignalSource.filename=/home/javier/signals/satgen_30mins/output/output +SignalSource.item_type=gr_complex +SignalSource.sampling_frequency=16368000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=./out.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through +DataTypeAdapter.item_type=gr_complex + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.dump=false +InputFilter.dump_filename=/media/javier/WDNASNTFS/output_5.456Msps_gr_complex.dat + +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 + +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 + +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 + +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 + +InputFilter.filter_type=lowpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=16368000 +InputFilter.IF=0 +InputFilter.decimation_factor=3 + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=6 +Channels_1B.count=0 +Channels_L5.count=0 +Channels_5X.count=0 + +Channels.in_acquisition=1 + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.threshold=3.0 +Acquisition_1C.use_CFAR_algorithm=false +Acquisition_1C.blocking=true +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=125 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### GALILEO ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.threshold=2.8 +Acquisition_1B.use_CFAR_algorithm=false +Acquisition_1B.blocking=false +Acquisition_1B.doppler_max=5000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_KF_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.dump=true +Tracking_1C.dump_filename=./tracking_ch_ +Tracking_1C.extend_correlation_symbols=20; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.early_late_space_narrow_chips=0.15 + +;Tracking_1C.code_disc_sd_chips=0.2; // Initial R +;Tracking_1C.carrier_disc_sd_rads=0.3; // Initial R + +;Tracking_1C.init_code_phase_sd_chips=0.5; // Initial P_0_0 +;Tracking_1C.init_carrier_phase_sd_rad=0.7; +;Tracking_1C.init_carrier_freq_sd_hz=5; +;Tracking_1C.init_carrier_freq_rate_sd_hz_s=1; + +;Tracking_1C.code_phase_sd_chips=0.15; // Initial Q +;Tracking_1C.carrier_phase_sd_rad=0.25; +;Tracking_1C.carrier_freq_sd_hz=0.6; +;Tracking_1C.carrier_freq_rate_sd_hz_s=0.01; + + +;######### TRACKING GALILEO CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=15.0; +Tracking_1B.dll_bw_hz=0.75; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.5; +Tracking_1B.early_late_space_narrow_chips=0.10; +Tracking_1B.very_early_late_space_narrow_chips=0.5; +Tracking_1B.pll_bw_narrow_hz=2.5 +Tracking_1B.dll_bw_narrow_hz=0.2 +Tracking_1B.extend_correlation_symbols=5 +Tracking_1B.track_pilot=true +Tracking_1B.enable_fll_pull_in=true; +;Tracking_1B.pull_in_time_s=60 +Tracking_1B.enable_fll_steady_state=false +Tracking_1B.fll_bw_hz=10 +Tracking_1B.dump=false +Tracking_1B.dump_filename=tracking_ch_ + +;######### TELEMETRY DECODER GALILEO CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +;#implementation: +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat +Observables.enable_carrier_smoothing=false +Observables.smoothing_factor=200 + + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.enable_rx_clock_correction=false +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=1000; +PVT.rinexobs_rate_ms=1000; +PVT.display_rate_ms=1000; +PVT.elevation_mask=15; +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT +PVT.enable_monitor=false +PVT.monitor_udp_port=1337 +PVT.monitor_client_addresses=127.0.0.1 + +;######### MONITOR CONFIG ############ +Monitor.enable_monitor=false +Monitor.decimation_factor=1 +Monitor.client_addresses=127.0.0.1 +Monitor.udp_port=1234 diff --git a/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_bin_file_III_1a.conf b/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_bin_file_III_1a.conf new file mode 100644 index 000000000..d7a72f476 --- /dev/null +++ b/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_bin_file_III_1a.conf @@ -0,0 +1,184 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2500000 + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Flexiband_Signal_Source +SignalSource.flag_read_file=true +SignalSource.signal_file=/datalogger/signals/Fraunhofer/L125_III1b_210s.usb ; <- PUT YOUR FILE HERE +SignalSource.item_type=gr_complex +SignalSource.firmware_file=flexiband_III-1b.bit +SignalSource.RF_channels=1 +;#frontend channels gain. Not usable yet! +SignalSource.gain1=0 +SignalSource.gain2=0 +SignalSource.gain3=0 +SignalSource.AGC=true +SignalSource.usb_packet_buffer=128 + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Pass_Through +DataTypeAdapter0.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter.dat +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.45 +InputFilter0.band2_begin=0.55 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=20000000 +InputFilter0.IF=0; +InputFilter0.decimation_factor=8 + +;######### RESAMPLER CONFIG 0 ############ +Resampler0.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 1 CONFIG ############ +DataTypeAdapter1.implementation=Pass_Through +DataTypeAdapter1.item_type=gr_complex + +;######### INPUT_FILTER 1 CONFIG ############ +InputFilter1.implementation=Pass_Through +InputFilter1.dump=false +InputFilter1.dump_filename=../data/input_filter.dat +InputFilter1.input_item_type=gr_complex +InputFilter1.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 1 ############ +Resampler1.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 2 CONFIG ############ +SignalConditioner2.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 2 CONFIG ############ +DataTypeAdapter2.implementation=Pass_Through +DataTypeAdapter2.item_type=gr_complex + +;######### INPUT_FILTER 2 CONFIG ############ +InputFilter2.implementation=Pass_Through +InputFilter2.dump=false +InputFilter2.dump_filename=../data/input_filter.dat +InputFilter2.input_item_type=gr_complex +InputFilter2.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 2 ############ +Resampler2.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 + +Channels.in_acquisition=1 + +;# CHANNEL CONNECTION +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +Channel4.RF_channel_ID=0 +Channel5.RF_channel_ID=0 +Channel6.RF_channel_ID=0 +Channel7.RF_channel_ID=0 + +;#signal: +Channel.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.extend_correlation_ms=10 +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.pll_bw_narrow_hz=35; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.dll_bw_narrow_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=true +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_III_1a.conf b/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_III_1a.conf new file mode 100644 index 000000000..48727d42f --- /dev/null +++ b/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_III_1a.conf @@ -0,0 +1,189 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2500000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Flexiband_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.firmware_file=flexiband_III-1a.bit +SignalSource.RF_channels=1 +;#frontend channels gain. Not usable yet! +SignalSource.gain1=0 +SignalSource.gain2=0 +SignalSource.gain3=0 +SignalSource.AGC=true +SignalSource.usb_packet_buffer=128 + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Pass_Through +DataTypeAdapter0.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter.dat +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.45 +InputFilter0.band2_begin=0.55 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=20000000 +InputFilter0.IF=-205000 +InputFilter0.decimation_factor=8 + +;######### RESAMPLER CONFIG 0 ############ +Resampler0.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 1 CONFIG ############ +DataTypeAdapter1.implementation=Pass_Through +DataTypeAdapter1.item_type=gr_complex + +;######### INPUT_FILTER 1 CONFIG ############ +InputFilter1.implementation=Pass_Through +InputFilter1.dump=false +InputFilter1.dump_filename=../data/input_filter.dat +InputFilter1.input_item_type=gr_complex +InputFilter1.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 1 ############ +Resampler1.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 2 CONFIG ############ +SignalConditioner2.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 2 CONFIG ############ +DataTypeAdapter2.implementation=Pass_Through +DataTypeAdapter2.item_type=gr_complex + +;######### INPUT_FILTER 2 CONFIG ############ +InputFilter2.implementation=Pass_Through +InputFilter2.dump=false +InputFilter2.dump_filename=../data/input_filter.dat +InputFilter2.input_item_type=gr_complex +InputFilter2.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 2 ############ +Resampler2.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 + +Channels.in_acquisition=1 + + +;# CHANNEL CONNECTION +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +Channel4.RF_channel_ID=0 +Channel5.RF_channel_ID=0 +Channel6.RF_channel_ID=0 +Channel7.RF_channel_ID=0 + +;#signal: +;#if the option is disabled by default is assigned "1C" GPS L1 C/A +Channel0.signal=1C +Channel1.signal=1C +Channel2.signal=1C +Channel3.signal=1C +Channel4.signal=1C +Channel5.signal=1C +Channel6.signal=1C +Channel7.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=3.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_III_1b.conf b/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_III_1b.conf new file mode 100644 index 000000000..478cc875d --- /dev/null +++ b/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_III_1b.conf @@ -0,0 +1,188 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2500000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Flexiband_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.firmware_file=flexiband_III-1b.bit +SignalSource.RF_channels=1 +;#frontend channels gain. Not usable yet! +SignalSource.gain1=0 +SignalSource.gain2=0 +SignalSource.gain3=0 +;#frontend channels AGC +SignalSource.AGC=true +SignalSource.usb_packet_buffer=128 + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Pass_Through +DataTypeAdapter0.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter.dat +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.45 +InputFilter0.band2_begin=0.55 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.IF=-205000 +InputFilter0.decimation_factor=8 + +;######### RESAMPLER CONFIG 0 ############ +Resampler0.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 1 CONFIG ############ +DataTypeAdapter1.implementation=Pass_Through +DataTypeAdapter1.item_type=gr_complex + +;######### INPUT_FILTER 1 CONFIG ############ +InputFilter1.implementation=Pass_Through +InputFilter1.dump=false +InputFilter1.dump_filename=../data/input_filter.dat +InputFilter1.input_item_type=gr_complex +InputFilter1.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 1 ############ +Resampler1.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 2 CONFIG ############ +SignalConditioner2.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 2 CONFIG ############ +DataTypeAdapter2.implementation=Pass_Through +DataTypeAdapter2.item_type=gr_complex + +;######### INPUT_FILTER 2 CONFIG ############ +InputFilter2.implementation=Pass_Through +InputFilter2.dump=false +InputFilter2.dump_filename=../data/input_filter.dat +InputFilter2.input_item_type=gr_complex +InputFilter2.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 2 ############ +Resampler2.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels.in_acquisition=1 + + +;# CHANNEL CONNECTION +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +Channel4.RF_channel_ID=0 +Channel5.RF_channel_ID=0 +Channel6.RF_channel_ID=0 +Channel7.RF_channel_ID=0 + +;#signal: +;#if the option is disabled by default is assigned "1C" GPS L1 C/A +Channel0.signal=1C +Channel1.signal=1C +Channel2.signal=1C +Channel3.signal=1C +Channel4.signal=1C +Channel5.signal=1C +Channel6.signal=1C +Channel7.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=3.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_II_3b.conf b/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_II_3b.conf new file mode 100644 index 000000000..3ba4ba52d --- /dev/null +++ b/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_II_3b.conf @@ -0,0 +1,195 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2500000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Flexiband_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.firmware_file=flexiband_II-3b.bit +SignalSource.RF_channels=1 +;#frontend channels gain. Not usable yet! +SignalSource.gain1=0 +SignalSource.gain2=0 +SignalSource.gain3=0 +SignalSource.AGC=true +SignalSource.usb_packet_buffer=128 + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Pass_Through +DataTypeAdapter0.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter.dat +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.45 +InputFilter0.band2_begin=0.55 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=40000000 +InputFilter0.IF=-205000 +InputFilter0.decimation_factor=16 + +;######### RESAMPLER CONFIG 0 ############ +Resampler0.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 1 CONFIG ############ +DataTypeAdapter1.implementation=Pass_Through +DataTypeAdapter1.item_type=gr_complex + +;######### INPUT_FILTER 1 CONFIG ############ +InputFilter1.implementation=Pass_Through +InputFilter1.dump=false +InputFilter1.dump_filename=../data/input_filter.dat +InputFilter1.input_item_type=gr_complex +InputFilter1.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 1 ############ +Resampler1.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 2 CONFIG ############ +SignalConditioner2.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 2 CONFIG ############ +DataTypeAdapter2.implementation=Pass_Through +DataTypeAdapter2.item_type=gr_complex + +;######### INPUT_FILTER 2 CONFIG ############ +InputFilter2.implementation=Pass_Through +InputFilter2.dump=false +InputFilter2.dump_filename=../data/input_filter.dat +InputFilter2.input_item_type=gr_complex +InputFilter2.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 2 ############ +Resampler2.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 + +Channels.in_acquisition=1 + +;#signal: +;# "1C" GPS L1 C/A +;# "1B" GALILEO E1 B (I/NAV OS/CS/SoL) +;# "1G" GLONASS L1 C/A +;# "2S" GPS L2 L2C (M) +;# "5X" GALILEO E5a I+Q +;# "L5" GPS L5 + +;# CHANNEL CONNECTION +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +Channel4.RF_channel_ID=0 +Channel5.RF_channel_ID=0 +Channel6.RF_channel_ID=0 +Channel7.RF_channel_ID=0 + +;#signal: +Channel0.signal=1C +Channel1.signal=1C +Channel2.signal=1C +Channel3.signal=1C +Channel4.signal=1C +Channel5.signal=1C +Channel6.signal=1C +Channel7.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=3.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_I_1b.conf b/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_I_1b.conf new file mode 100644 index 000000000..73624bc73 --- /dev/null +++ b/conf/File_input/gnss-sdr_multichannel_GPS_L1_Flexiband_realtime_I_1b.conf @@ -0,0 +1,183 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=5000000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Flexiband_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.firmware_file=flexiband_I-1b.bit +SignalSource.RF_channels=1 +;#frontend channels gain. Not usable yet! +SignalSource.gain1=0 +SignalSource.gain2=0 +SignalSource.gain3=0 +SignalSource.AGC=true +SignalSource.usb_packet_buffer=128 + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Pass_Through +DataTypeAdapter0.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter.dat +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.45 +InputFilter0.band2_begin=0.55 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=40000000 +InputFilter0.IF=-205000 +InputFilter0.decimation_factor=8 + +;######### RESAMPLER CONFIG 0 ############ +Resampler0.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 1 CONFIG ############ +DataTypeAdapter1.implementation=Pass_Through +DataTypeAdapter1.item_type=gr_complex + +;######### INPUT_FILTER 1 CONFIG ############ +InputFilter1.implementation=Pass_Through +InputFilter1.dump=false +InputFilter1.dump_filename=../data/input_filter.dat +InputFilter1.input_item_type=gr_complex +InputFilter1.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 1 ############ +Resampler1.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 2 CONFIG ############ +SignalConditioner2.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 2 CONFIG ############ +DataTypeAdapter2.implementation=Pass_Through +DataTypeAdapter2.item_type=gr_complex + +;######### INPUT_FILTER 2 CONFIG ############ +InputFilter2.implementation=Pass_Through +InputFilter2.dump=false +InputFilter2.dump_filename=../data/input_filter.dat +InputFilter2.input_item_type=gr_complex +InputFilter2.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 2 ############ +Resampler2.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=4 +Channels.in_acquisition=1 + + +;# CHANNEL CONNECTION +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +;Channel4.RF_channel_ID=0 +;Channel5.RF_channel_ID=0 +;Channel6.RF_channel_ID=0 +;Channel7.RF_channel_ID=0 + +;#signal: +Channel0.signal=1C +Channel1.signal=1C +Channel2.signal=1C +Channel3.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=3.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_multichannel_GPS_L1_L2_Flexiband_realtime_III_1b.conf b/conf/File_input/gnss-sdr_multichannel_GPS_L1_L2_Flexiband_realtime_III_1b.conf new file mode 100644 index 000000000..9e77cb6ae --- /dev/null +++ b/conf/File_input/gnss-sdr_multichannel_GPS_L1_L2_Flexiband_realtime_III_1b.conf @@ -0,0 +1,305 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2500000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Flexiband_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.firmware_file=flexiband_III-1b.bit +SignalSource.RF_channels=2 +;#frontend channels gain. Not usable yet! +SignalSource.gain1=0 +SignalSource.gain2=0 +SignalSource.gain3=0 +SignalSource.AGC=true +SignalSource.usb_packet_buffer=128 + +;###################################################### +;######### RF CHANNEL 0 SIGNAL CONDITIONER ############ +;###################################################### + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Pass_Through +DataTypeAdapter0.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter.dat +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.45 +InputFilter0.band2_begin=0.55 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=20000000 +InputFilter0.IF=-205000 +InputFilter0.decimation_factor=8 + +;######### RESAMPLER CONFIG 0 ############ +Resampler0.implementation=Pass_Through + +;###################################################### +;######### RF CHANNEL 1 SIGNAL CONDITIONER ############ +;###################################################### + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 1 CONFIG ############ +DataTypeAdapter1.implementation=Pass_Through +DataTypeAdapter1.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter1.implementation=Freq_Xlating_Fir_Filter +InputFilter1.dump=false +InputFilter1.dump_filename=../data/input_filter_ch1.dat +InputFilter1.input_item_type=gr_complex +InputFilter1.output_item_type=gr_complex +InputFilter1.taps_item_type=float +InputFilter1.number_of_taps=5 +InputFilter1.number_of_bands=2 +InputFilter1.band1_begin=0.0 +InputFilter1.band1_end=0.45 +InputFilter1.band2_begin=0.55 +InputFilter1.band2_end=1.0 +InputFilter1.ampl1_begin=1.0 +InputFilter1.ampl1_end=1.0 +InputFilter1.ampl2_begin=0.0 +InputFilter1.ampl2_end=0.0 +InputFilter1.band1_error=1.0 +InputFilter1.band2_error=1.0 +InputFilter1.filter_type=bandpass +InputFilter1.grid_density=16 +InputFilter1.sampling_frequency=20000000 +InputFilter1.IF=100000 +InputFilter1.decimation_factor=8 + + +;######### RESAMPLER CONFIG 1 ############ +Resampler1.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 2 CONFIG ############ +SignalConditioner2.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 2 CONFIG ############ +DataTypeAdapter2.implementation=Pass_Through +DataTypeAdapter2.item_type=gr_complex + +;######### INPUT_FILTER 2 CONFIG ############ +InputFilter2.implementation=Pass_Through +InputFilter2.dump=false +InputFilter2.dump_filename=../data/input_filter.dat +InputFilter2.input_item_type=gr_complex +InputFilter2.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 2 ############ +Resampler2.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels_2S.count=8 +Channels.in_acquisition=1 + +;#signal: +;# "1C" GPS L1 C/A +;# "1B" GALILEO E1 B (I/NAV OS/CS/SoL) +;# "1G" GLONASS L1 C/A +;# "2S" GPS L2 L2C (M) +;# "5X" GALILEO E5a I+Q +;# "L5" GPS L5 + + +;# CHANNEL CONNECTION +Channel0.RF_channel_ID=0 +Channel0.signal=1C + +Channel1.RF_channel_ID=0 +Channel1.signal=1C + +Channel2.RF_channel_ID=0 +Channel2.signal=1C + +Channel3.RF_channel_ID=0 +Channel3.signal=1C + +Channel4.RF_channel_ID=0 +Channel4.signal=1C + +Channel5.RF_channel_ID=0 +Channel5.signal=1C + +Channel6.RF_channel_ID=0 +Channel6.signal=1C + +Channel7.RF_channel_ID=0 +Channel7.signal=1C + + +Channel8.RF_channel_ID=1 +Channel8.signal=2S + +Channel9.RF_channel_ID=1 +Channel9.signal=2S + +Channel10.RF_channel_ID=1 +Channel10.signal=2S + +Channel11.RF_channel_ID=1 +Channel11.signal=2S + +Channel12.RF_channel_ID=1 +Channel12.signal=2S + +Channel13.RF_channel_ID=1 +Channel13.signal=2S + +Channel14.RF_channel_ID=1 +Channel14.signal=2S + +Channel15.RF_channel_ID=1 +Channel15.signal=2S + +Channel8.RF_channel_ID=1 +Channel8.signal=2S + +Channel9.RF_channel_ID=1 +Channel9.signal=2S + +Channel10.RF_channel_ID=1 +Channel10.signal=2S + +Channel11.RF_channel_ID=1 +Channel11.signal=2S + +Channel12.RF_channel_ID=1 +Channel12.signal=2S + +Channel13.RF_channel_ID=1 +Channel13.signal=2S + +Channel14.RF_channel_ID=1 +Channel14.signal=2S + +Channel15.RF_channel_ID=1 +Channel15.signal=2S + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=3.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=true +Tracking_1C.dump_filename=./tracking_ch_ + + +;# GPS L2C M +Acquisition_2S.implementation=GPS_L2_M_PCPS_Acquisition +Acquisition_2S.item_type=gr_complex +Acquisition_2S.pfa=0.01 +;Acquisition_2S.pfa=0.001 +Acquisition_2S.doppler_max=5000 +Acquisition_2S.doppler_min=-5000 +Acquisition_2S.doppler_step=30 +Acquisition_2S.max_dwells=1 +Acquisition_2S.dump=false +Acquisition_2S.dump_filename=./acq_dump.dat + +Tracking_2S.implementation=GPS_L2_M_DLL_PLL_Tracking +Tracking_2S.item_type=gr_complex +Tracking_2S.pll_bw_hz=1.5; +Tracking_2S.dll_bw_hz=0.3; +Tracking_2S.order=3; +Tracking_2S.early_late_space_chips=0.5; +Tracking_2S.dump=true +Tracking_2S.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER GPS L1 CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### TELEMETRY DECODER GPS L2 CONFIG ############ +TelemetryDecoder_2S.implementation=GPS_L2C_Telemetry_Decoder +TelemetryDecoder_2S.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.flag_averaging=true +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_multichannel_GPS_L1_L2_Galileo_E1B_Flexiband_bin_file_III_1b.conf b/conf/File_input/gnss-sdr_multichannel_GPS_L1_L2_Galileo_E1B_Flexiband_bin_file_III_1b.conf new file mode 100644 index 000000000..f2a47b807 --- /dev/null +++ b/conf/File_input/gnss-sdr_multichannel_GPS_L1_L2_Galileo_E1B_Flexiband_bin_file_III_1b.conf @@ -0,0 +1,278 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2500000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.nokia.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Flexiband_Signal_Source +SignalSource.flag_read_file=true +SignalSource.signal_file=/datalogger/signals/Fraunhofer/L125_III1b_210s.usb ; <- PUT YOUR FILE HERE +SignalSource.item_type=gr_complex +SignalSource.firmware_file=flexiband_III-1b.bit +SignalSource.RF_channels=2 +;#frontend channels gain. Not usable yet! +SignalSource.gain1=0 +SignalSource.gain2=0 +SignalSource.gain3=0 +SignalSource.AGC=true +SignalSource.usb_packet_buffer=128 + +;###################################################### +;######### RF CHANNEL 0 SIGNAL CONDITIONER ############ +;###################################################### + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Pass_Through +DataTypeAdapter0.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter.dat +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.45 +InputFilter0.band2_begin=0.55 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=20000000 +InputFilter0.IF=0 +InputFilter0.decimation_factor=8 + +;######### RESAMPLER CONFIG 0 ############ +Resampler0.implementation=Pass_Through + +;###################################################### +;######### RF CHANNEL 1 SIGNAL CONDITIONER ############ +;###################################################### + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 1 CONFIG ############ +DataTypeAdapter1.implementation=Pass_Through +DataTypeAdapter1.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter1.implementation=Freq_Xlating_Fir_Filter +InputFilter1.dump=false +InputFilter1.dump_filename=../data/input_filter_ch1.dat +InputFilter1.input_item_type=gr_complex +InputFilter1.output_item_type=gr_complex +InputFilter1.taps_item_type=float +InputFilter1.number_of_taps=5 +InputFilter1.number_of_bands=2 +InputFilter1.band1_begin=0.0 +InputFilter1.band1_end=0.45 +InputFilter1.band2_begin=0.55 +InputFilter1.band2_end=1.0 +InputFilter1.ampl1_begin=1.0 +InputFilter1.ampl1_end=1.0 +InputFilter1.ampl2_begin=0.0 +InputFilter1.ampl2_end=0.0 +InputFilter1.band1_error=1.0 +InputFilter1.band2_error=1.0 +InputFilter1.filter_type=bandpass +InputFilter1.grid_density=16 +InputFilter1.sampling_frequency=20000000 +InputFilter1.IF=0 +InputFilter1.decimation_factor=8 + + +;######### RESAMPLER CONFIG 1 ############ +Resampler1.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 2 CONFIG ############ +SignalConditioner2.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 2 CONFIG ############ +DataTypeAdapter2.implementation=Pass_Through +DataTypeAdapter2.item_type=gr_complex + +;######### INPUT_FILTER 2 CONFIG ############ +InputFilter2.implementation=Pass_Through +InputFilter2.dump=false +InputFilter2.dump_filename=../data/input_filter.dat +InputFilter2.input_item_type=gr_complex +InputFilter2.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 2 ############ +Resampler2.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############. +Channels_1C.count=2 +Channels_1B.count=4 +Channels_2S.count=4 + +Channels.in_acquisition=1 + +;#signal: +;# "1C" GPS L1 C/A +;# "1B" GALILEO E1 B (I/NAV OS/CS/SoL) +;# "1G" GLONASS L1 C/A +;# "2S" GPS L2 L2C (M) +;# "5X" GALILEO E5a I+Q +;# "L5" GPS L5 + + +;# CHANNEL CONNECTION +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=1 +Channel3.RF_channel_ID=1 +Channel4.RF_channel_ID=1 +Channel5.RF_channel_ID=1 +Channel6.RF_channel_ID=0 +Channel7.RF_channel_ID=0 +Channel8.RF_channel_ID=0 +Channel9.RF_channel_ID=0 +Channel10.RF_channel_ID=1 +Channel11.RF_channel_ID=1 +Channel12.RF_channel_ID=1 +Channel13.RF_channel_ID=1 +Channel14.RF_channel_ID=1 +Channel15.RF_channel_ID=1 + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=1.5; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; + +;# GPS L2C M +Acquisition_2S.implementation=GPS_L2_M_PCPS_Acquisition +Acquisition_2S.item_type=gr_complex +Acquisition_2S.pfa=0.01 +;Acquisition_2S.pfa=0.001 +Acquisition_2S.doppler_max=5000 +Acquisition_2S.doppler_min=-5000 +Acquisition_2S.doppler_step=30 +Acquisition_2S.max_dwells=1 +Acquisition_2S.dump=false +Acquisition_2S.dump_filename=./acq_dump.dat + +Tracking_2S.implementation=GPS_L2_M_DLL_PLL_Tracking +Tracking_2S.item_type=gr_complex +Tracking_2S.pll_bw_hz=1.5; +Tracking_2S.dll_bw_hz=0.3; +Tracking_2S.order=3; +Tracking_2S.early_late_space_chips=0.5; +Tracking_2S.dump=true +Tracking_2S.dump_filename=../data/epl_tracking_ch_ + + +;# GALILEO E1B +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +;Acquisition_1B.threshold=0 +Acquisition_1B.pfa=0.0000005 +Acquisition_1B.doppler_max=5000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + + +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=15.0; +Tracking_1B.dll_bw_hz=2.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=./veml_tracking_ch_ + + +;######### TELEMETRY DECODER GPS L1 CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### TELEMETRY DECODER GPS L2 CONFIG ############ +TelemetryDecoder_2S.implementation=GPS_L2C_Telemetry_Decoder +TelemetryDecoder_2S.dump=false + +;######### TELEMETRY DECODER GALILEO E1B CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=100 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_multichannel_GPS_L2_M_Flexiband_bin_file_III_1b.conf b/conf/File_input/gnss-sdr_multichannel_GPS_L2_M_Flexiband_bin_file_III_1b.conf new file mode 100644 index 000000000..c6ca7e8e0 --- /dev/null +++ b/conf/File_input/gnss-sdr_multichannel_GPS_L2_M_Flexiband_bin_file_III_1b.conf @@ -0,0 +1,363 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=5000000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Flexiband_Signal_Source +SignalSource.flag_read_file=true +SignalSource.signal_file=/media/javier/SISTEMA/signals/fraunhofer/L125_III1b_210s.usb ; <- PUT YOUR FILE HERE +SignalSource.item_type=gr_complex +SignalSource.firmware_file=flexiband_III-1b.bit +SignalSource.RF_channels=1 +;#frontend channels gain. Not usable yet! +SignalSource.gain1=0 +SignalSource.gain2=0 +SignalSource.gain3=0 +SignalSource.AGC=true +SignalSource.usb_packet_buffer=128 + +;###################################################### +;######### RF CHANNEL 0 SIGNAL CONDITIONER ############ +;###################################################### + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Pass_Through +DataTypeAdapter0.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter_ch0.dat +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.45 +InputFilter0.band2_begin=0.55 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=20000000 +InputFilter0.IF=0 +InputFilter0.decimation_factor=4 + +;######### RESAMPLER CONFIG 0 ############ +Resampler0.implementation=Pass_Through + +;###################################################### +;######### RF CHANNEL 1 SIGNAL CONDITIONER ############ +;###################################################### + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 1 CONFIG ############ +DataTypeAdapter1.implementation=Pass_Through +DataTypeAdapter1.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter1.implementation=Freq_Xlating_Fir_Filter +InputFilter1.dump=false +InputFilter1.dump_filename=../data/input_filter_ch1.dat +InputFilter1.input_item_type=gr_complex +InputFilter1.output_item_type=gr_complex +InputFilter1.taps_item_type=float +InputFilter1.number_of_taps=5 +InputFilter1.number_of_bands=2 +InputFilter1.band1_begin=0.0 +InputFilter1.band1_end=0.45 +InputFilter1.band2_begin=0.55 +InputFilter1.band2_end=1.0 +InputFilter1.ampl1_begin=1.0 +InputFilter1.ampl1_end=1.0 +InputFilter1.ampl2_begin=0.0 +InputFilter1.ampl2_end=0.0 +InputFilter1.band1_error=1.0 +InputFilter1.band2_error=1.0 +InputFilter1.filter_type=bandpass +InputFilter1.grid_density=16 +InputFilter1.sampling_frequency=20000000 +InputFilter1.IF=0 +InputFilter1.decimation_factor=4 + + +;######### RESAMPLER CONFIG 1 ############ +Resampler1.implementation=Pass_Through + + +;###################################################### +;######### RF CHANNEL 2 SIGNAL CONDITIONER ############ +;###################################################### + +;######### SIGNAL_CONDITIONER 2 CONFIG ############ +SignalConditioner2.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 2 CONFIG ############ +DataTypeAdapter2.implementation=Pass_Through +DataTypeAdapter2.item_type=gr_complex + +;######### INPUT_FILTER 2 CONFIG ############ +InputFilter2.implementation=Freq_Xlating_Fir_Filter +InputFilter2.dump=false +InputFilter2.dump_filename=../data/input_filter_ch2.dat +InputFilter2.input_item_type=gr_complex +InputFilter2.output_item_type=gr_complex +InputFilter2.taps_item_type=float +InputFilter2.number_of_taps=5 +InputFilter2.number_of_bands=2 +InputFilter2.band1_begin=0.0 +InputFilter2.band1_end=0.45 +InputFilter2.band2_begin=0.55 +InputFilter2.band2_end=1.0 +InputFilter2.ampl1_begin=1.0 +InputFilter2.ampl1_end=1.0 +InputFilter2.ampl2_begin=0.0 +InputFilter2.ampl2_end=0.0 +InputFilter2.band1_error=1.0 +InputFilter2.band2_error=1.0 +InputFilter2.filter_type=bandpass +InputFilter2.grid_density=16 +InputFilter2.sampling_frequency=40000000 +InputFilter2.IF=0 +InputFilter2.decimation_factor=8 + + +;######### RESAMPLER CONFIG 1 ############ +Resampler2.implementation=Pass_Through + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=0 +Channels_1B.count=10 +Channels_2S.count=0 +Channels_5X.count=0 + +Channels.in_acquisition=1 + +;#signal: +;# "1C" GPS L1 C/A +;# "1B" GALILEO E1 B (I/NAV OS/CS/SoL) +;# "1G" GLONASS L1 C/A +;# "2S" GPS L2 L2C (M) +;# "5X" GALILEO E5a I+Q +;# "L5" GPS L5 +;# CHANNEL NUMBERING ORDER: GPS L1 C/A, GPS L2 L2C (M), GALILEO E1 B, GALILEO E5a + +;# CHANNEL CONNECTION + +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +Channel4.RF_channel_ID=0 +Channel5.RF_channel_ID=0 +Channel6.RF_channel_ID=0 +Channel7.RF_channel_ID=0 +Channel8.RF_channel_ID=0 +Channel9.RF_channel_ID=0 +Channel10.RF_channel_ID=0 +Channel11.RF_channel_ID=0 +Channel12.RF_channel_ID=0 +Channel13.RF_channel_ID=0 +Channel14.RF_channel_ID=0 +Channel15.RF_channel_ID=0 +Channel16.RF_channel_ID=0 +Channel17.RF_channel_ID=0 +Channel18.RF_channel_ID=0 +Channel19.RF_channel_ID=0 +Channel20.RF_channel_ID=0 +Channel21.RF_channel_ID=0 +Channel22.RF_channel_ID=0 +Channel23.RF_channel_ID=0 +Channel24.RF_channel_ID=0 +Channel25.RF_channel_ID=0 +Channel26.RF_channel_ID=0 +Channel27.RF_channel_ID=0 +Channel28.RF_channel_ID=0 +Channel29.RF_channel_ID=0 +Channel30.RF_channel_ID=2 +Channel31.RF_channel_ID=2 +Channel32.RF_channel_ID=2 +Channel33.RF_channel_ID=2 +Channel34.RF_channel_ID=2 +Channel35.RF_channel_ID=2 +Channel36.RF_channel_ID=2 +Channel37.RF_channel_ID=2 +Channel38.RF_channel_ID=2 +Channel39.RF_channel_ID=2 + +;######### ACQUISITION CONFIG ###### + +;# GPS L1 CA +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + +;# Galileo E1 +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +;Acquisition_1B.threshold=0 +Acquisition_1B.pfa=0.0000002 +Acquisition_1B.doppler_max=5000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + + +;# GPS L2C M +Acquisition_2S.implementation=GPS_L2_M_PCPS_Acquisition +Acquisition_2S.item_type=gr_complex +Acquisition_2S.pfa=0.01 +;Acquisition_2S.pfa=0.001 +Acquisition_2S.doppler_max=5000 +Acquisition_2S.doppler_min=-5000 +Acquisition_2S.doppler_step=60 +Acquisition_2S.max_dwells=1 +Acquisition_2S.dump=false +Acquisition_2S.dump_filename=./acq_dump.dat + + +;# GALILEO E5a +Acquisition_5X.implementation=Galileo_E5a_Noncoherent_IQ_Acquisition_CAF +Acquisition_5X.item_type=gr_complex +Acquisition_5X.coherent_integration_time_ms=1 +Acquisition_5X.threshold=0.009 +Acquisition_5X.doppler_max=5000 +Acquisition_5X.doppler_step=125 +Acquisition_5X.bit_transition_flag=false +Acquisition_5X.max_dwells=1 +Acquisition_5X.CAF_window_hz=0 ; **Only for E5a** Resolves doppler ambiguity averaging the specified BW in the winner code delay. If set to 0 CAF filter is desactivated. Recommended value 3000 Hz +Acquisition_5X.Zero_padding=0 ; **Only for E5a** Avoids power loss and doppler ambiguity in bit transitions by correlating one code with twice the input data length, ensuring that at least one full code is present without transitions. If set to 1 it is ON, if set to 0 it is OFF. +Acquisition_5X.dump=false +Acquisition_5X.dump_filename=./acq_dump.dat + + +;######### TRACKING CONFIG ############ +;######### GPS L1 C/A GENERIC TRACKING CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=3.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### GALILEO E1 TRK CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=15.0; +Tracking_1B.dll_bw_hz=2.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### GPS L2C GENERIC TRACKING CONFIG ############ +Tracking_2S.implementation=GPS_L2_M_DLL_PLL_Tracking +Tracking_2S.item_type=gr_complex +Tracking_2S.pll_bw_hz=2.0; +Tracking_2S.dll_bw_hz=0.25; +Tracking_2S.order=2; +Tracking_2S.early_late_space_chips=0.5; +Tracking_2S.dump=false +Tracking_2S.dump_filename=./tracking_ch_ + + +;######### GALILEO E5 TRK CONFIG ############ +Tracking_5X.implementation=Galileo_E5a_DLL_PLL_Tracking +Tracking_5X.item_type=gr_complex +Tracking_5X.pll_bw_hz_init=20.0; **Only for E5a** PLL loop filter bandwidth during initialization [Hz] +Tracking_5X.dll_bw_hz_init=20.0; **Only for E5a** DLL loop filter bandwidth during initialization [Hz] +Tracking_5X.ti_ms=1; **Only for E5a** loop filter integration time after initialization (secondary code delay search)[ms] +Tracking_5X.pll_bw_hz=20.0; +Tracking_5X.dll_bw_hz=20.0; +Tracking_5X.order=2; +Tracking_5X.early_late_space_chips=0.5; +Tracking_5X.dump=false +Tracking_5X.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + +TelemetryDecoder_2S.implementation=GPS_L2C_Telemetry_Decoder +TelemetryDecoder_2S.dump=false + +TelemetryDecoder_5X.implementation=Galileo_E5a_Telemetry_Decoder +TelemetryDecoder_5X.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=100 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_multichannel_GPS_L2_M_Flexiband_bin_file_III_1b_real.conf b/conf/File_input/gnss-sdr_multichannel_GPS_L2_M_Flexiband_bin_file_III_1b_real.conf new file mode 100644 index 000000000..0abf4188c --- /dev/null +++ b/conf/File_input/gnss-sdr_multichannel_GPS_L2_M_Flexiband_bin_file_III_1b_real.conf @@ -0,0 +1,258 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=5000000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Flexiband_Signal_Source +SignalSource.flag_read_file=true +SignalSource.signal_file=/home/javier/signals/20140923_20-24-17_L125_roof_210s.usb ; <- PUT YOUR FILE HERE +SignalSource.item_type=gr_complex +SignalSource.firmware_file=flexiband_III-1b.bit +SignalSource.RF_channels=2 +;#frontend channels gain. Not usable yet! +SignalSource.gain1=0 +SignalSource.gain2=0 +SignalSource.gain3=0 +SignalSource.AGC=true +SignalSource.usb_packet_buffer=128 + +;###################################################### +;######### RF CHANNEL 0 SIGNAL CONDITIONER ############ +;###################################################### + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Pass_Through +DataTypeAdapter0.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter_ch0.dat +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.45 +InputFilter0.band2_begin=0.55 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.IF=0 +InputFilter0.decimation_factor=4 + +;######### RESAMPLER CONFIG 0 ############ +Resampler0.implementation=Pass_Through + +;###################################################### +;######### RF CHANNEL 1 SIGNAL CONDITIONER ############ +;###################################################### + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 1 CONFIG ############ +DataTypeAdapter1.implementation=Pass_Through +DataTypeAdapter1.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter1.implementation=Freq_Xlating_Fir_Filter +InputFilter1.dump=false +InputFilter1.dump_filename=../data/input_filter_ch1.dat +InputFilter1.input_item_type=gr_complex +InputFilter1.output_item_type=gr_complex +InputFilter1.taps_item_type=float +InputFilter1.number_of_taps=5 +InputFilter1.number_of_bands=2 +InputFilter1.band1_begin=0.0 +InputFilter1.band1_end=0.45 +InputFilter1.band2_begin=0.55 +InputFilter1.band2_end=1.0 +InputFilter1.ampl1_begin=1.0 +InputFilter1.ampl1_end=1.0 +InputFilter1.ampl2_begin=0.0 +InputFilter1.ampl2_end=0.0 +InputFilter1.band1_error=1.0 +InputFilter1.band2_error=1.0 +InputFilter1.filter_type=bandpass +InputFilter1.grid_density=16 +InputFilter1.sampling_frequency=20000000 +InputFilter1.IF=0 +InputFilter1.decimation_factor=4 + + +;######### RESAMPLER CONFIG 1 ############ +Resampler1.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 2 CONFIG ############ +SignalConditioner2.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 2 CONFIG ############ +DataTypeAdapter2.implementation=Pass_Through +DataTypeAdapter2.item_type=gr_complex + +;######### INPUT_FILTER 2 CONFIG ############ +InputFilter2.implementation=Pass_Through +InputFilter2.dump=false +InputFilter2.dump_filename=../data/input_filter.dat +InputFilter2.input_item_type=gr_complex +InputFilter2.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 2 ############ +Resampler2.implementation=Pass_Through + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=10 +Channels_2S.count=4 + +;#GPS.prns=7,8 + +Channels.in_acquisition=1 + +;#signal: +;# "1C" GPS L1 C/A +;# "1B" GALILEO E1 B (I/NAV OS/CS/SoL) +;# "1G" GLONASS L1 C/A +;# "2S" GPS L2 L2C (M) +;# "5X" GALILEO E5a I+Q +;# "L5" GPS L5 +;# CHANNEL NUMBERING ORDER: GPS L1 C/A, GPS L2 L2C (M), GALILEO E1 B, GALILEO E5a + +;# CHANNEL CONNECTION +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +Channel4.RF_channel_ID=0 +Channel5.RF_channel_ID=0 +Channel6.RF_channel_ID=0 +Channel7.RF_channel_ID=0 +Channel8.RF_channel_ID=0 +Channel9.RF_channel_ID=0 +Channel10.RF_channel_ID=1 +Channel11.RF_channel_ID=1 +Channel12.RF_channel_ID=1 +Channel13.RF_channel_ID=1 +Channel14.RF_channel_ID=1 +Channel15.RF_channel_ID=1 +Channel16.RF_channel_ID=1 +Channel17.RF_channel_ID=1 +Channel18.RF_channel_ID=1 +Channel19.RF_channel_ID=1 + + +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;# GPS L2C M +Acquisition_2S.implementation=GPS_L2_M_PCPS_Acquisition +Acquisition_2S.item_type=gr_complex +Acquisition_2S.pfa=0.01 +;Acquisition_2S.pfa=0.001 +Acquisition_2S.doppler_max=5000 +Acquisition_2S.doppler_min=-5000 +Acquisition_2S.doppler_step=60 +Acquisition_2S.max_dwells=1 +Acquisition_2S.dump=false +Acquisition_2S.dump_filename=./acq_dump.dat + + +;######### TRACKING CONFIG ############ +;######### GPS L1 C/A GENERIC TRACKING CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=3.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### GPS L2C GENERIC TRACKING CONFIG ############ +Tracking_2S.implementation=GPS_L2_M_DLL_PLL_Tracking +Tracking_2S.item_type=gr_complex +Tracking_2S.pll_bw_hz=2.0; +Tracking_2S.dll_bw_hz=0.25; +Tracking_2S.order=2; +Tracking_2S.early_late_space_chips=0.5; +Tracking_2S.dump=false +Tracking_2S.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +TelemetryDecoder_2S.implementation=GPS_L2C_Telemetry_Decoder +TelemetryDecoder_2S.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=true +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=100 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_multichannel_all_in_one_Flexiband_bin_file_III_1b.conf b/conf/File_input/gnss-sdr_multichannel_all_in_one_Flexiband_bin_file_III_1b.conf new file mode 100644 index 000000000..a9ec9e564 --- /dev/null +++ b/conf/File_input/gnss-sdr_multichannel_all_in_one_Flexiband_bin_file_III_1b.conf @@ -0,0 +1,385 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=5000000 +GNSS-SDR.Galileo_banned_prns=14,18 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Flexiband_Signal_Source +SignalSource.flag_read_file=true +SignalSource.signal_file=/media/javier/SISTEMA/signals/fraunhofer/L125_III1b_210s.usb ; <- PUT YOUR FILE HERE +SignalSource.item_type=gr_complex +SignalSource.firmware_file=flexiband_III-1b.bit +SignalSource.RF_channels=3 +;#frontend channels gain. Not usable yet! +SignalSource.gain1=0 +SignalSource.gain2=0 +SignalSource.gain3=0 +SignalSource.AGC=true +SignalSource.usb_packet_buffer=128 + +;###################################################### +;######### RF CHANNEL 0 SIGNAL CONDITIONER ############ +;###################################################### + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Pass_Through +DataTypeAdapter0.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter_ch0.dat +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.45 +InputFilter0.band2_begin=0.55 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.IF=0 +InputFilter0.decimation_factor=4 + +;######### RESAMPLER CONFIG 0 ############ +Resampler0.implementation=Pass_Through + + +;###################################################### +;######### RF CHANNEL 1 SIGNAL CONDITIONER ############ +;###################################################### + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 1 CONFIG ############ +DataTypeAdapter1.implementation=Pass_Through +DataTypeAdapter1.item_type=gr_complex + +;######### INPUT_FILTER 1 CONFIG ############ +InputFilter1.implementation=Freq_Xlating_Fir_Filter +InputFilter1.dump=false +InputFilter1.dump_filename=../data/input_filter_ch1.dat +InputFilter1.input_item_type=gr_complex +InputFilter1.output_item_type=gr_complex +InputFilter1.taps_item_type=float +InputFilter1.number_of_taps=5 +InputFilter1.number_of_bands=2 +InputFilter1.band1_begin=0.0 +InputFilter1.band1_end=0.45 +InputFilter1.band2_begin=0.55 +InputFilter1.band2_end=1.0 +InputFilter1.ampl1_begin=1.0 +InputFilter1.ampl1_end=1.0 +InputFilter1.ampl2_begin=0.0 +InputFilter1.ampl2_end=0.0 +InputFilter1.band1_error=1.0 +InputFilter1.band2_error=1.0 +InputFilter1.filter_type=bandpass +InputFilter1.grid_density=16 +InputFilter1.IF=0 +InputFilter1.decimation_factor=4 + +;######### RESAMPLER CONFIG 1 ############ +Resampler1.implementation=Pass_Through + + +;###################################################### +;######### RF CHANNEL 2 SIGNAL CONDITIONER ############ +;###################################################### + +;######### SIGNAL_CONDITIONER 2 CONFIG ############ +SignalConditioner2.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 2 CONFIG ############ +DataTypeAdapter2.implementation=Pass_Through +DataTypeAdapter2.item_type=gr_complex + +;######### INPUT_FILTER 2 CONFIG ############ +InputFilter2.implementation=Freq_Xlating_Fir_Filter +InputFilter2.dump=false +InputFilter2.dump_filename=../data/input_filter_ch2.dat +InputFilter2.input_item_type=gr_complex +InputFilter2.output_item_type=gr_complex +InputFilter2.taps_item_type=float +InputFilter2.number_of_taps=5 +InputFilter2.number_of_bands=2 +InputFilter2.band1_begin=0.0 +InputFilter2.band1_end=0.45 +InputFilter2.band2_begin=0.55 +InputFilter2.band2_end=1.0 +InputFilter2.ampl1_begin=1.0 +InputFilter2.ampl1_end=1.0 +InputFilter2.ampl2_begin=0.0 +InputFilter2.ampl2_end=0.0 +InputFilter2.band1_error=1.0 +InputFilter2.band2_error=1.0 +InputFilter2.filter_type=bandpass +InputFilter2.grid_density=16 +InputFilter2.IF=0 +InputFilter2.decimation_factor=8 + + +;######### RESAMPLER CONFIG 2 ############ +Resampler2.implementation=Pass_Through + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=10 +Channels_1B.count=10 +Channels_2S.count=10 +Channels_5X.count=2 +Channels_L5.count=2 + +;#GPS.prns=7,8 +;Channels.in_acquisition=2 + +;# CHANNEL CONNECTION + +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +Channel4.RF_channel_ID=0 +Channel5.RF_channel_ID=0 +Channel6.RF_channel_ID=0 +Channel7.RF_channel_ID=0 +Channel8.RF_channel_ID=0 +Channel9.RF_channel_ID=0 +Channel10.RF_channel_ID=1 +Channel11.RF_channel_ID=1 +Channel12.RF_channel_ID=1 +Channel13.RF_channel_ID=1 +Channel14.RF_channel_ID=1 +Channel15.RF_channel_ID=1 +Channel16.RF_channel_ID=1 +Channel17.RF_channel_ID=1 +Channel18.RF_channel_ID=1 +Channel19.RF_channel_ID=1 +Channel20.RF_channel_ID=0 +Channel21.RF_channel_ID=0 +Channel22.RF_channel_ID=0 +Channel23.RF_channel_ID=0 +Channel24.RF_channel_ID=0 +Channel25.RF_channel_ID=0 +Channel26.RF_channel_ID=0 +Channel27.RF_channel_ID=0 +Channel28.RF_channel_ID=0 +Channel29.RF_channel_ID=0 +Channel30.RF_channel_ID=2 +Channel31.RF_channel_ID=2 +Channel32.RF_channel_ID=2 +Channel33.RF_channel_ID=2 +Channel34.RF_channel_ID=2 +Channel35.RF_channel_ID=2 +Channel36.RF_channel_ID=2 +Channel37.RF_channel_ID=2 +Channel38.RF_channel_ID=2 +Channel39.RF_channel_ID=2 +Channel40.RF_channel_ID=2 +Channel41.RF_channel_ID=2 +Channel42.RF_channel_ID=2 + +;Channel20.satellite=7 + + +;# GPS L1 CA +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;# Galileo E1 +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +;Acquisition_1B.threshold=0 +Acquisition_1B.pfa=0.0000002 +Acquisition_1B.doppler_max=5000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.dump_filename=./acq_dump.dat + + +;# GPS L2C M +Acquisition_2S.implementation=GPS_L2_M_PCPS_Acquisition +Acquisition_2S.item_type=gr_complex +Acquisition_2S.pfa=0.01 +;Acquisition_2S.pfa=0.001 +Acquisition_2S.doppler_max=5000 +Acquisition_2S.doppler_min=-5000 +Acquisition_2S.doppler_step=60 +Acquisition_2S.max_dwells=1 +Acquisition_2S.dump=false +Acquisition_2S.dump_filename=./acq_dump.dat + + +;# GALILEO E5a +Acquisition_5X.implementation=Galileo_E5a_Noncoherent_IQ_Acquisition_CAF +Acquisition_5X.item_type=gr_complex +Acquisition_5X.coherent_integration_time_ms=1 +Acquisition_5X.threshold=0.009 +Acquisition_5X.doppler_max=5000 +Acquisition_5X.doppler_step=125 +Acquisition_5X.bit_transition_flag=false +Acquisition_5X.max_dwells=1 +Acquisition_5X.CAF_window_hz=0 ; **Only for E5a** Resolves doppler ambiguity averaging the specified BW in the winner code delay. If set to 0 CAF filter is desactivated. Recommended value 3000 Hz +Acquisition_5X.Zero_padding=0 ; **Only for E5a** Avoids power loss and doppler ambiguity in bit transitions by correlating one code with twice the input data length, ensuring that at least one full code is present without transitions. If set to 1 it is ON, if set to 0 it is OFF. +Acquisition_5X.dump=false +Acquisition_5X.dump_filename=./acq_dump.dat + + +;# GPS L5 +Acquisition_L5.implementation=GPS_L5i_PCPS_Acquisition +Acquisition_L5.item_type=gr_complex +Acquisition_L5.pfa=0.01 +;Acquisition_L5.pfa=0.001 +Acquisition_L5.doppler_max=5000 +Acquisition_L5.doppler_min=-5000 +Acquisition_L5.doppler_step=125 +Acquisition_L5.max_dwells=1 +Acquisition_L5.dump=false +Acquisition_L5.dump_filename=./acq_dump.dat + + + +;######### TRACKING CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=35.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + +;######### GALILEO E1 TRK CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=15.0; +Tracking_1B.dll_bw_hz=2.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### GPS L2C GENERIC TRACKING CONFIG ############ +Tracking_2S.implementation=GPS_L2_M_DLL_PLL_Tracking +Tracking_2S.item_type=gr_complex +Tracking_2S.pll_bw_hz=2.0; +Tracking_2S.dll_bw_hz=0.25; +Tracking_2S.order=2; +Tracking_2S.early_late_space_chips=0.5; +Tracking_2S.dump=false +Tracking_2S.dump_filename=./tracking_ch_ + +;######### GALILEO E5 TRK CONFIG ############ +Tracking_5X.implementation=Galileo_E5a_DLL_PLL_Tracking +Tracking_5X.item_type=gr_complex +Tracking_5X.track_pilot=true +Tracking_5X.pll_bw_hz=15.0; +Tracking_5X.dll_bw_hz=2.0; +Tracking_5X.pll_bw_narrow_hz=5.0; +Tracking_5X.dll_bw_narrow_hz=1.0; +Tracking_5X.order=2; +Tracking_5X.early_late_space_chips=0.5; +Tracking_5X.dump=false +Tracking_5X.dump_filename=./tracking_ch_ + +;######### GALILEO E5 TRK CONFIG ############ +Tracking_L5.implementation=GPS_L5_DLL_PLL_Tracking +Tracking_L5.item_type=gr_complex +Tracking_L5.track_pilot=true +Tracking_L5.pll_bw_hz=15.0; +Tracking_L5.dll_bw_hz=2.0; +Tracking_L5.pll_bw_narrow_hz=4.0; +Tracking_L5.dll_bw_narrow_hz=1.0; +Tracking_L5.order=2; +Tracking_L5.early_late_space_chips=0.5; +Tracking_L5.dump=false +Tracking_L5.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + +TelemetryDecoder_2S.implementation=GPS_L2C_Telemetry_Decoder +TelemetryDecoder_2S.dump=false + +TelemetryDecoder_5X.implementation=Galileo_E5a_Telemetry_Decoder +TelemetryDecoder_5X.dump=false + +TelemetryDecoder_L5.implementation=GPS_L5_Telemetry_Decoder +TelemetryDecoder_L5.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=10 +PVT.display_rate_ms=100 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/File_input/gnss-sdr_multisource_Hybrid_ishort.conf b/conf/File_input/gnss-sdr_multisource_Hybrid_ishort.conf new file mode 100644 index 000000000..5838a3b88 --- /dev/null +++ b/conf/File_input/gnss-sdr_multisource_Hybrid_ishort.conf @@ -0,0 +1,169 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 + +GNSS-SDR.num_sources=2 + +SignalSource.enable_throttle_control=false +SignalSource.repeat=false + + +;######### SIGNAL_SOURCE 0 CONFIG ############ +SignalSource0.implementation=File_Signal_Source +SignalSource0.filename=/datalogger/signals/CTTC/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE +SignalSource0.item_type=ishort +SignalSource0.sampling_frequency=4000000 +SignalSource0.samples=0 + + +;######### SIGNAL_SOURCE 1 CONFIG ############ +SignalSource1.implementation=File_Signal_Source +SignalSource1.filename=/datalogger/signals/CTTC/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE +SignalSource1.item_type=ishort +SignalSource1.sampling_frequency=4000000 +SignalSource1.freq=1575420000 +SignalSource1.samples=0 + + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Ishort_To_Complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Pass_Through +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter.dat +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex + + + +;######### RESAMPLER 1 CONFIG ############ +Resampler1.implementation=Pass_Through +Resampler1.dump=false +Resampler1.dump_filename=../data/resampler.dat +Resampler1.item_type=gr_complex +Resampler1.sample_freq_in=4000000 +Resampler1.sample_freq_out=4000000 + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 1 CONFIG ############ +DataTypeAdapter1.implementation=Ishort_To_Complex + +;######### INPUT_FILTER 1 CONFIG ############ +InputFilter1.implementation=Pass_Through +InputFilter1.dump=false + + +;######### RESAMPLER 1 CONFIG ############ +Resampler1.implementation=Pass_Through +Resampler1.dump=false +Resampler1.dump_filename=../data/resampler.dat. +Resampler1.item_type=gr_complex +Resampler1.sample_freq_in=4000000 +Resampler1.sample_freq_out=4000000 + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=2 +Channels_1B.count=2 +Channels.in_acquisition=1 + + +;# CHANNEL CONNECTION +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=1 +Channel3.RF_channel_ID=1 +;#signal: +;#if the option is disabled by default is assigned "1C" GPS L1 C/A +Channel.signal=1B + + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.015 +;Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### GALILEO ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +;Acquisition_1B.threshold=0 +Acquisition_1B.pfa=0.0000008 +Acquisition_1B.doppler_max=15000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=45.0; +Tracking_1C.dll_bw_hz=4.0; +Tracking_1C.order=3; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TRACKING GALILEO CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=15.0; +Tracking_1B.dll_bw_hz=2.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### TELEMETRY DECODER GALILEO CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.output_rate_ms=100; +PVT.display_rate_ms=500; +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump_filename=./PVT +PVT.dump=false diff --git a/conf/File_input/gnss-sdr_multisource_Hybrid_nsr.conf b/conf/File_input/gnss-sdr_multisource_Hybrid_nsr.conf new file mode 100644 index 000000000..c5c5e9134 --- /dev/null +++ b/conf/File_input/gnss-sdr_multisource_Hybrid_nsr.conf @@ -0,0 +1,231 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +GNSS-SDR.num_sources=2 + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +;GNSS-SDR.internal_fs_sps=6826700 +GNSS-SDR.internal_fs_sps=2560000 +;GNSS-SDR.internal_fs_sps=4096000 +;GNSS-SDR.internal_fs_sps=5120000 + +SignalSource.enable_throttle_control=false +SignalSource.repeat=false + + +;######### SIGNAL_SOURCE 0 CONFIG ############ +SignalSource0.implementation=Nsr_File_Signal_Source +SignalSource0.filename=/datalogger/signals/ifen/E1L1_FE0_Band0.stream ; <- PUT YOUR FILE HERE +SignalSource0.item_type=byte +SignalSource0.sampling_frequency=20480000 +SignalSource0.samples=0 + + +;######### SIGNAL_SOURCE 1 CONFIG ############ +SignalSource1.implementation=Nsr_File_Signal_Source +SignalSource1.filename=/datalogger/signals/ifen/E1L1_FE0_Band0.stream +SignalSource1.item_type=byte +SignalSource1.sampling_frequency=20480000 +SignalSource1.samples=0 + + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Pass_Through +DataTypeAdapter0.item_type=float + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Freq_Xlating_Fir_Filter +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter.dat +InputFilter0.input_item_type=float +InputFilter0.output_item_type=gr_complex +InputFilter0.taps_item_type=float +InputFilter0.number_of_taps=5 +InputFilter0.number_of_bands=2 +InputFilter0.band1_begin=0.0 +InputFilter0.band1_end=0.45 +InputFilter0.band2_begin=0.55 +InputFilter0.band2_end=1.0 +InputFilter0.ampl1_begin=1.0 +InputFilter0.ampl1_end=1.0 +InputFilter0.ampl2_begin=0.0 +InputFilter0.ampl2_end=0.0 +InputFilter0.band1_error=1.0 +InputFilter0.band2_error=1.0 +InputFilter0.filter_type=bandpass +InputFilter0.grid_density=16 +InputFilter0.sampling_frequency=20480000 +InputFilter0.IF=5499998.47412109 +InputFilter0.decimation_factor=8 + +;######### RESAMPLER CONFIG 0 ############ +Resampler0.implementation=Pass_Through + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER 1 CONFIG ############ +DataTypeAdapter1.implementation=Pass_Through +DataTypeAdapter1.item_type=float + +;######### INPUT_FILTER 1 CONFIG ############ +InputFilter1.implementation=Freq_Xlating_Fir_Filter +InputFilter1.dump=false +InputFilter1.dump_filename=../data/input_filter.dat +InputFilter1.input_item_type=float +InputFilter1.output_item_type=gr_complex +InputFilter1.taps_item_type=float +InputFilter1.number_of_taps=5 +InputFilter1.number_of_bands=2 +InputFilter1.band1_begin=0.0 +InputFilter1.band1_end=0.45 +InputFilter1.band2_begin=0.55 +InputFilter1.band2_end=1.0 +InputFilter1.ampl1_begin=1.0 +InputFilter1.ampl1_end=1.0 +InputFilter1.ampl2_begin=0.0 +InputFilter1.ampl2_end=0.0 +InputFilter1.band1_error=1.0 +InputFilter1.band2_error=1.0 +InputFilter1.filter_type=bandpass +InputFilter1.grid_density=16 +InputFilter1.sampling_frequency=20480000 +InputFilter1.IF=5499998.47412109 +InputFilter1.decimation_factor=8 + + +;######### RESAMPLER CONFIG 1 ############ +Resampler1.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels_1B.count=8 +Channels.in_acquisition=1 + +;# SOURCE CONNECTION +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +Channel4.RF_channel_ID=0 +Channel5.RF_channel_ID=0 +Channel6.RF_channel_ID=0 +Channel7.RF_channel_ID=0 + +Channel8.RF_channel_ID=1 +Channel9.RF_channel_ID=1 +Channel10.RF_channel_ID=1 +Channel11.RF_channel_ID=1 +Channel12.RF_channel_ID=1 +Channel13.RF_channel_ID=1 +Channel14.RF_channel_ID=1 +Channel15.RF_channel_ID=1 + +;#signal: +;#if the option is disabled by default is assigned "1C" GPS L1 C/A +Channel0.signal=1C +Channel1.signal=1C +Channel2.signal=1C +Channel3.signal=1C +Channel4.signal=1C +Channel5.signal=1C +Channel6.signal=1C +Channel7.signal=1B +Channel8.signal=1B +Channel9.signal=1B +Channel10.signal=1B +Channel11.signal=1B +Channel12.signal=1B +Channel13.signal=1B +Channel14.signal=1B +Channel15.signal=1B + + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.scoherent_integration_time_ms=1 +Acquisition_1C.pfa=0.015 +;Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### GALILEO ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +;Acquisition_1B.threshold=0 +Acquisition_1B.pfa=0.0000002 +Acquisition_1B.doppler_max=15000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=45.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TRACKING GALILEO CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=15.0; +Tracking_1B.dll_bw_hz=2.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### TELEMETRY DECODER GALILEO CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=true; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/Nsr_input/gnss-sdr_GPS_L1_nsr.conf b/conf/Nsr_input/gnss-sdr_GPS_L1_nsr.conf new file mode 100644 index 000000000..d0682aa30 --- /dev/null +++ b/conf/Nsr_input/gnss-sdr_GPS_L1_nsr.conf @@ -0,0 +1,164 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; Sample configuration file for IFEN SX-NSR software receiver front-end +; https://www.ifen.com/products/sx3-gnss-software-receiver/ +; This sample configuration is able to process directly .sream binary files +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2560000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=false +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Nsr_File_Signal_Source +SignalSource.filename=/home/javier/Descargas/RoofTop_FE0_Band1.stream ; <- PUT YOUR FILE HERE +SignalSource.item_type=byte +SignalSource.sampling_frequency=20480000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through +DataTypeAdapter.item_type=float + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat +InputFilter.input_item_type=float +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=20480000 +#InputFilter.IF=5499998.47412109 +InputFilter.IF=5679999.2370605494 +InputFilter.decimation_factor=8 + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat +Resampler.item_type=gr_complex + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=0 +Channels_2S.count=8 +Channels.in_acquisition=1 + + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.scoherent_integration_time_ms=1 +Acquisition_1C.pfa=0.015 +;Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + +Acquisition_2S.implementation=GPS_L2_M_PCPS_Acquisition +Acquisition_2S.item_type=gr_complex +Acquisition_2S.coherent_integration_time_ms=20 +Acquisition_2S.pfa=0.01 +Acquisition_2S.doppler_max=5000 +Acquisition_2S.doppler_step=100 +Acquisition_2S.bit_transition_flag=false +Acquisition_2S.max_dwells=1 +Acquisition_2S.dump=false +Acquisition_2S.dump_filename=./acq_dump.dat + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=45.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + +;######### GPS L2C GENERIC TRACKING CONFIG ############ +Tracking_2S.implementation=GPS_L2_M_DLL_PLL_Tracking +Tracking_2S.item_type=gr_complex +Tracking_2S.pll_bw_hz=1.5; +Tracking_2S.dll_bw_hz=0.4; +Tracking_2S.order=2; +Tracking_2S.early_late_space_chips=0.5; +Tracking_2S.dump=true +Tracking_2S.dump_filename=../data/epl_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + +TelemetryDecoder_2S.implementation=GPS_L2C_Telemetry_Decoder +TelemetryDecoder_2S.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=true diff --git a/conf/Nsr_input/gnss-sdr_GPS_L1_nsr_gauss.conf b/conf/Nsr_input/gnss-sdr_GPS_L1_nsr_gauss.conf new file mode 100644 index 000000000..a127a5870 --- /dev/null +++ b/conf/Nsr_input/gnss-sdr_GPS_L1_nsr_gauss.conf @@ -0,0 +1,207 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +;GNSS-SDR.internal_fs_sps=6826700 +GNSS-SDR.internal_fs_sps=2560000 +;GNSS-SDR.internal_fs_sps=4096000 +;GNSS-SDR.internal_fs_sps=5120000 + +;######### SIGNAL_SOURCE CONFIG ############ +;#implementation: Use [File_Signal_Source] [Nsr_File_Signal_Source] or [UHD_Signal_Source] +SignalSource.implementation=Nsr_File_Signal_Source + +;#filename: path to file with the captured GNSS signal samples to be processed +SignalSource.filename=/home/javier/signals/ifen/E1L1_FE0_Band0.stream ; <- PUT YOUR FILE HERE + +;#item_type: Type and resolution for each of the signal samples. Use only gr_complex in this version. +SignalSource.item_type=byte + +;#sampling_frequency: Original Signal sampling frequency in [Hz] +SignalSource.sampling_frequency=20480000 + +;#freq: RF front-end center frequency in [Hz] +SignalSource.freq=1575420000 + +;#samples: Number of samples to be processed. Notice that 0 indicates the entire file. +SignalSource.samples=0 + +;#repeat: Repeat the processing file. Disable this option in this version +SignalSource.repeat=false + +;#dump: Dump the Signal source data to a file. Disable this option in this version +SignalSource.dump=false + +SignalSource.dump_filename=../data/signal_source.dat + + +;#enable_throttle_control: Enabling this option tells the signal source to keep the delay between samples in post processing. +; it helps to not overload the CPU, but the processing time will be longer. +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +;## It holds blocks to change data type, filter and resample input data. + +;#implementation: Use [Pass_Through] or [Signal_Conditioner] +;#[Pass_Through] disables this block and the [DataTypeAdapter], [InputFilter] and [Resampler] blocks +;#[Signal_Conditioner] enables this block. Then you have to configure [DataTypeAdapter], [InputFilter] and [Resampler] blocks +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +;## Changes the type of input data. +;#implementation: [Pass_Through] disables this block +DataTypeAdapter.implementation=Pass_Through +DataTypeAdapter.item_type=float + +;######### INPUT_FILTER CONFIG ############ +;## Filter the input data. Can be combined with frequency translation for IF signals + +;#implementation: Use [Pass_Through] or [Fir_Filter] or [Freq_Xlating_Fir_Filter] +;#[Freq_Xlating_Fir_Filter] enables FIR filter and a composite frequency translation +;# that shifts IF down to zero Hz. + +InputFilter.implementation=Freq_Xlating_Fir_Filter + +;#dump: Dump the filtered data to a file. +InputFilter.dump=false + +;#dump_filename: Log path and filename. +InputFilter.dump_filename=../data/input_filter.dat + +;#The following options are used in the filter design of Fir_Filter and Freq_Xlating_Fir_Filter implementation. +;#These options are based on parameters of gnuradio's function: gr_remez. +;#These function calculates the optimal (in the Chebyshev/minimax sense) FIR filter inpulse +;#reponse given a set of band edges, the desired reponse on those bands, +;#and the weight given to the error in those bands. + +;#input_item_type: Type and resolution for input signal samples. Use only gr_complex in this version. +InputFilter.input_item_type=float + +;#outut_item_type: Type and resolution for output filtered signal samples. Use only gr_complex in this version. +InputFilter.output_item_type=gr_complex + +;#taps_item_type: Type and resolution for the taps of the filter. Use only float in this version. +InputFilter.taps_item_type=float + +;#number_of_taps: Number of taps in the filter. Increasing this parameter increases the processing time +InputFilter.number_of_taps=5 + +;#number_of _bands: Number of frequency bands in the filter. +InputFilter.number_of_bands=2 + +;#bands: frequency at the band edges [ b1 e1 b2 e2 b3 e3 ...]. +;#Frequency is in the range [0, 1], with 1 being the Nyquist frequency (Fs/2) +;#The number of band_begin and band_end elements must match the number of bands + +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 + +;#ampl: desired amplitude at the band edges [ a(b1) a(e1) a(b2) a(e2) ...]. +;#The number of ampl_begin and ampl_end elements must match the number of bands + +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 + +;#band_error: weighting applied to each band (usually 1). +;#The number of band_error elements must match the number of bands +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 + +;#filter_type: one of "bandpass", "hilbert" or "differentiator" +InputFilter.filter_type=bandpass + +;#grid_density: determines how accurately the filter will be constructed. +;The minimum value is 16; higher values are slower to compute the filter. +InputFilter.grid_density=16 + +;# Original sampling frequency stored in the signal file +InputFilter.sampling_frequency=20480000 + +;#The following options are used only in Freq_Xlating_Fir_Filter implementation. +;#InputFilter.IF is the intermediate frequency (in Hz) shifted down to zero Hz + +InputFilter.IF=5499998.47412109 + +;# Decimation factor after the frequency tranaslating block +InputFilter.decimation_factor=8 + + +;######### RESAMPLER CONFIG ############ +;## Resamples the input data. + +;#implementation: Use [Pass_Through] or [Direct_Resampler] +;#[Pass_Through] disables this block +;#[Direct_Resampler] enables a resampler that implements a nearest neighbourhood interpolation +Resampler.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +;#count: Number of available GPS satellite channels. +Channels_1C.count=8 +Channels.in_acquisition=1 +#Channel.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat +Acquisition_1C.item_type=gr_complex +Acquisition_1C.if=0 +Acquisition_1C.sampled_ms=1 +Acquisition_1C.threshold=2.5 +;Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=100 + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_Gaussian_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.if=0 +Tracking_1C.dump=true +Tracking_1C.dump_filename=../data/epl_tracking_ch_ +Tracking_1C.pll_bw_hz=15.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.order=3; + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false +TelemetryDecoder_1C.decimation_factor=1; + +;######### OBSERVABLES CONFIG ############ +;#implementation: +Observables.implementation=Hybrid_Observables + +;#dump: Enable or disable the Observables internal binary data file logging [true] or [false] +Observables.dump=false + +;#dump_filename: Log path and filename. +Observables.dump_filename=./observables.dat + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=true diff --git a/conf/Nsr_input/gnss-sdr_Hybrid_nsr.conf b/conf/Nsr_input/gnss-sdr_Hybrid_nsr.conf new file mode 100644 index 000000000..91bbc1c69 --- /dev/null +++ b/conf/Nsr_input/gnss-sdr_Hybrid_nsr.conf @@ -0,0 +1,176 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2560000 + + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Nsr_File_Signal_Source +SignalSource.filename=/home/javier/signals/ifen/E1L1_FE0_Band0.stream ; <- PUT YOUR FILE HERE +SignalSource.item_type=byte +SignalSource.sampling_frequency=20480000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through +DataTypeAdapter.item_type=float + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.input_item_type=float +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=20480000 +InputFilter.IF=5499998.47412109 +InputFilter.decimation_factor=8 +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=10 +Channels_1B.count=10 +Channels.in_acquisition=1 + +;#signal: +;# "1C" GPS L1 C/A +;# "1B" GALILEO E1 B (I/NAV OS/CS/SoL) +;# "1G" GLONASS L1 C/A +;# "2S" GPS L2 L2C (M) +;# "5X" GALILEO E5a I+Q +;# "L5" GPS L5 + +;#if the option is disabled by default is assigned "1C" GPS L1 C/A +Channel0.signal=1C +Channel1.signal=1C +Channel2.signal=1C +Channel3.signal=1C +Channel4.signal=1C +Channel5.signal=1C +Channel6.signal=1C +Channel7.signal=1C +Channel8.signal=1C +Channel9.signal=1C +Channel10.signal=1B +Channel11.signal=1B +Channel12.signal=1B +Channel13.signal=1B +Channel14.signal=1B +Channel15.signal=1B +Channel16.signal=1B +Channel17signal=1B +Channel18.signal=1B +Channel19.signal=1B + + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.threshold=2.5 +Acquisition_1C.blocking=true +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### GALILEO ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.threshold=2.5 +Acquisition_1B.blocking=true +Acquisition_1B.doppler_max=5000 +Acquisition_1B.doppler_step=250 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.extend_correlation_ms=1 +Tracking_1C.pll_bw_hz=40; +Tracking_1C.pll_bw_narrow_hz=30; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.dll_bw_narrow_hz=1.5; +Tracking_1C.order=2; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TRACKING GALILEO CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=20.0; +Tracking_1B.dll_bw_hz=2.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### TELEMETRY DECODER GALILEO CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### OBSERVABLES CONFIG ############ +;#implementation: +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=10; +PVT.display_rate_ms=500; +PVT.elevation_mask=20; +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/Other/front-end-cal.conf b/conf/Other/front-end-cal.conf new file mode 100644 index 000000000..29efe2347 --- /dev/null +++ b/conf/Other/front-end-cal.conf @@ -0,0 +1,206 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; Default configuration file +; You can define your own front-end calibration tool configuration and invoke it by doing +; ./front-end-cal --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### INITIAL RECEIVER POSITIION ###### +; san francisco scenario +;GNSS-SDR.init_latitude_deg=40.74846557442795 +;GNSS-SDR.init_longitude_deg=-73.98593961814200 +;GNSS-SDR.init_altitude_m=329.11968943169342 + +; Barcelona CTTC +;GNSS-SDR.init_latitude_deg=41.27719585553101 +;GNSS-SDR.init_longitude_deg=1.988782985790802 +;GNSS-SDR.init_altitude_m=10 + +; Mozoncillo +;GNSS-SDR.init_latitude_deg=41.14534824586196 +;GNSS-SDR.init_longitude_deg=-4.187125019737464 +;GNSS-SDR.init_altitude_m=900 + +; ICEBAR - Jukkasjarvi +GNSS-SDR.init_latitude_deg=67.849722 +GNSS-SDR.init_longitude_deg=20.594444 +GNSS-SDR.init_altitude_m=325 + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2048000 + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=true +GNSS-SDR.SUPL_read_gps_assistance_xml=false +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=240 +GNSS-SDR.SUPL_MNC=08 +GNSS-SDR.SUPL_LAC=46003 +GNSS-SDR.SUPL_CI=425950 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Osmosdr_Signal_Source +;#freq: RF front-end center frequency in [Hz] +SignalSource.freq=1575420000 +;#item_type: Type and resolution for each of the signal samples. Use only gr_complex in this version. +SignalSource.item_type=gr_complex +;#sampling_frequency: Original Signal sampling frequency in samples per second +SignalSource.sampling_frequency=2048000 +;#gain: Front-end Gain in [dB] +SignalSource.gain=40 +SignalSource.rf_gain=40 +SignalSource.if_gain=30 +SignalSource.AGC_enabled=false + +;# Please note that the new RTL-SDR Blog V3 dongles ship a < 1 PPM +;# temperature compensated oscillator (TCXO), which is well suited for GNSS +;# signal processing, and a 4.5 V powered bias-tee to feed an active antenna. +;# Whether the bias-tee is turned off before reception depends on which version +;# of gr-osmosdr was used when compiling GNSS-SDR. With an old version +;# (for example, v0.1.4-8), the utility rtl_biast may be used to switch the +;# bias-tee, and then call gnss-sdr. +;# See https://github.com/rtlsdrblog/rtl_biast +;# After reception the bias-tee is switched off automatically by the program. +;# With newer versions of gr-osmosdr (>= 0.1.4-13), the bias-tee can be +;# activated by uncommenting the following line: +;SignalSource.osmosdr_args=rtl,bias=1 + +;#samples: Number of samples to be processed. Notice that 0 means infinite samples. +SignalSource.samples=0 + +;#repeat: Repeat the processing file. +SignalSource.repeat=false + +;#dump: Dump the Signal source data to a file. +SignalSource.dump=false + +SignalSource.dump_filename=../data/signal_source.dat + +;######### SIGNAL_CONDITIONER CONFIG ############ +;## It holds blocks to change data type, filter and resample input data. + +;#implementation: Use [Pass_Through] or [Signal_Conditioner] +;#[Pass_Through] disables this block and the [DataTypeAdapter], [InputFilter] and [Resampler] blocks +;#[Signal_Conditioner] enables this block. Then you have to configure [DataTypeAdapter], [InputFilter] and [Resampler] blocks +SignalConditioner.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER CONFIG ############ +;## Changes the type of input data. +;#implementation: Use [Ishort_To_Complex] or [Pass_Through] +DataTypeAdapter.implementation=Pass_Through +;#dump: Dump the filtered data to a file. +DataTypeAdapter.dump=false +;#dump_filename: Log path and filename. +DataTypeAdapter.dump_filename=../data/data_type_adapter.dat + +;######### INPUT_FILTER CONFIG ############ +;## Filter the input data. Can be combined with frequency translation for IF signals + +;#implementation: Use [Pass_Through] or [Fir_Filter] or [Freq_Xlating_Fir_Filter] +;#[Pass_Through] disables this block +;#[Fir_Filter] enables a FIR Filter +;#[Freq_Xlating_Fir_Filter] enables FIR filter and a composite frequency translation that shifts IF down to zero Hz. + +InputFilter.implementation=Freq_Xlating_Fir_Filter + +;#The following options are used in the filter design of Fir_Filter and Freq_Xlating_Fir_Filter implementation. +;#These options are based on parameters of gnuradio's function: gr_remez. +;#This function calculates the optimal (in the Chebyshev/minimax sense) FIR filter impulse response given a set of band edges, +;#the desired response on those bands, and the weight given to the error in those bands. + +;#input_item_type: Type and resolution for input signal samples. +InputFilter.input_item_type=gr_complex + +;#outut_item_type: Type and resolution for output filtered signal samples. +InputFilter.output_item_type=gr_complex + +;#taps_item_type: Type and resolution for the taps of the filter. Use only float in this version. +InputFilter.taps_item_type=float + +;#number_of_taps: Number of taps in the filter. Increasing this parameter increases the processing time +InputFilter.number_of_taps=5 + +;#number_of _bands: Number of frequency bands in the filter. +InputFilter.number_of_bands=2 + +;#bands: frequency at the band edges [ b1 e1 b2 e2 b3 e3 ...]. +;#Frequency is in the range [0, 1], with 1 being the Nyquist frequency (Fs/2) +;#The number of band_begin and band_end elements must match the number of bands + +InputFilter.band1_begin=0.0 +;InputFilter.band1_end=0.8 +InputFilter.band1_end=0.85 +InputFilter.band2_begin=0.90 +InputFilter.band2_end=1.0 + +;#ampl: desired amplitude at the band edges [ a(b1) a(e1) a(b2) a(e2) ...]. +;#The number of ampl_begin and ampl_end elements must match the number of bands + +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 + +;#band_error: weighting applied to each band (usually 1). +;#The number of band_error elements must match the number of bands +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 + +;#filter_type: one of "bandpass", "hilbert" or "differentiator" +InputFilter.filter_type=bandpass + +;#grid_density: determines how accurately the filter will be constructed. +;The minimum value is 16; higher values are slower to compute the filter. +InputFilter.grid_density=16 + +;#The following options are used only in Freq_Xlating_Fir_Filter implementation. +;#InputFilter.IF is the intermediate frequency (in Hz) shifted down to zero Hz + +InputFilter.sampling_frequency=2000000 +InputFilter.IF=0 + +InputFilter.decimation_factor=1 + +;#dump: Dump the filtered data to a file. +InputFilter.dump=false + +;#dump_filename: Log path and filename. +InputFilter.dump_filename=../data/input_filter.dat + +;######### RESAMPLER CONFIG ############ +;## Resamples the input data. +;#implementation: Use [Pass_Through] or [Direct_Resampler] +;#[Pass_Through] disables this block +Resampler.implementation=Pass_Through + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition_Fine_Doppler +;#item_type: Type and resolution for each of the signal samples. Use only gr_complex in this version. +Acquisition.item_type=gr_complex +;#sampled_ms: Signal block duration for the acquisition signal detection [ms] +Acquisition.sampled_ms=1 +;#threshold: Acquisition threshold +Acquisition.threshold=0.015 +;#doppler_max: Maximum expected Doppler shift [Hz] +Acquisition.doppler_max=100000 +;#doppler_max: Maximum expected Doppler shift [Hz] +Acquisition.doppler_min=-100000 +;#doppler_step Doppler step in the grid search [Hz] +Acquisition.doppler_step=500 +;#maximum dwells +Acquisition.max_dwells=15 +;#dump: Enable or disable the acquisition internal data file logging [true] or [false] +Acquisition.dump=false +;#filename: Log path and filename +Acquisition.dump_filename=./acq_dump.dat diff --git a/conf/Other/gnss-sdr_GPS_L1_2ch_udp.conf b/conf/Other/gnss-sdr_GPS_L1_2ch_udp.conf new file mode 100644 index 000000000..c25dc85f9 --- /dev/null +++ b/conf/Other/gnss-sdr_GPS_L1_2ch_udp.conf @@ -0,0 +1,103 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [Sps]. +GNSS-SDR.internal_fs_sps=13250000 ;//66.25/5 +;GNSS-SDR.internal_fs_sps=6625000 ;//66.25/10 +;GNSS-SDR.internal_fs_sps=3312500 ;//66.25/20 +;GNSS-SDR.internal_fs_sps=2650000 ;//66.25/25 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Custom_UDP_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.origin_address=0.0.0.0 +SignalSource.capture_device=eth0 +SignalSource.port=1234 +SignalSource.payload_bytes=1472 +;SignalSource.sample_type=cbyte +SignalSource.sample_type=c4bits +SignalSource.IQ_swap=false +SignalSource.RF_channels=1 +SignalSource.channels_in_udp=2 +SignalSource.dump=false +SignalSource.dump_filename=./signal_source.dat + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Pass_Through +;SignalConditioner0.implementation=Pass_Through +;SignalConditioner1.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels.in_acquisition=1 + +;# CHANNEL CONNECTION +Channel.signal=1C +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=0 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=0 +Channel4.RF_channel_ID=0 +Channel5.RF_channel_ID=0 +Channel6.RF_channel_ID=0 +Channel7.RF_channel_ID=0 +Channel8.RF_channel_ID=1 +Channel9.RF_channel_ID=1 + +;Channel0.signal=1C +;Channel1.RF_channel_ID=1 +;Channel1.signal=1C + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.threshold=2.5 +Acquisition_1C.blocking=false +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ +Tracking_1C.pll_bw_hz=35.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.early_late_space_chips=0.5; + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false diff --git a/conf/Other/gnss-sdr_GPS_L1_FPGA.conf b/conf/Other/gnss-sdr_GPS_L1_FPGA.conf new file mode 100644 index 000000000..c873f60cc --- /dev/null +++ b/conf/Other/gnss-sdr_GPS_L1_FPGA.conf @@ -0,0 +1,72 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=12500000 +GNSS-SDR.enable_FPGA=true + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Ad9361_Fpga_Signal_Source +SignalSource.sampling_frequency=12500000 +SignalSource.freq=1575420000 +SignalSource.switch_position=2 +SignalSource.gain_mode_rx1=slow_attack + +;######### CHANNELS GLOBAL CONFIG ############ +Channels.in_acquisition=1 +Channels_1C.count=12 + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition_Fpga +Acquisition_1C.threshold=2.0 +Acquisition_1C.doppler_max=50000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.make_two_steps=true +Acquisition_1C.second_nbins=3 +Acquisition_1C.doppler_step2=250 +Acquisition_1C.max_num_acqs=100 + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking_Fpga +Tracking_1C.extend_correlation_symbols=20 +Tracking_1C.pll_bw_hz=35; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.pll_bw_narrow_hz=5.0; +Tracking_1C.dll_bw_narrow_hz=0.50; +Tracking_1C.fll_bw_hz=10 +Tracking_1C.enable_fll_pull_in=true; +Tracking_1C.enable_fll_steady_state=false +Tracking_1C.high_dyn=true +Tracking_1C.dump=false +Tracking_1C.dump_filename=tracking_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single +PVT.iono_model=OFF +PVT.trop_model=OFF +PVT.raim_fde=1 +PVT.output_rate_ms=20; +PVT.display_rate_ms=500; +PVT.elevation_mask=0; +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/Other/gnss-sdr_GPS_L1_fifo.conf b/conf/Other/gnss-sdr_GPS_L1_fifo.conf new file mode 100644 index 000000000..a339ffb35 --- /dev/null +++ b/conf/Other/gnss-sdr_GPS_L1_fifo.conf @@ -0,0 +1,56 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2021 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=25000000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Fifo_Signal_Source +SignalSource.filename=fifo.fifo ; example usage: mkfifo fifo.fifo && cat path_to.bin >> fifo.fifo +SignalSource.sample_type=ishort; ; sample representation in fifo stream - will always output gr_complex +SignalSource.dump=false +;SignalSource.dump_filename=dump + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels.in_acquisition=1 +Channel.signal=1C + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=4.0; + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.iono_model=Broadcast +PVT.trop_model=Saastamoinen +PVT.output_path=./files diff --git a/conf/Other/gnss-sdr_GPS_L1_gr_complex_gpu.conf b/conf/Other/gnss-sdr_GPS_L1_gr_complex_gpu.conf new file mode 100644 index 000000000..c1b99441b --- /dev/null +++ b/conf/Other/gnss-sdr_GPS_L1_gr_complex_gpu.conf @@ -0,0 +1,85 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 + + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/datalogger/signals/Agilent/New York/4msps.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=gr_complex +SignalSource.samples=250000000 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Pass_Through + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels.in_acquisition=1 +Channel.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=0.005 +;Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking_GPU +Tracking_1C.item_type=gr_complex +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ +Tracking_1C.pll_bw_hz=45.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.order=3; + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=10 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false diff --git a/conf/Other/gnss-sdr_GPS_L1_monitor.conf b/conf/Other/gnss-sdr_GPS_L1_monitor.conf new file mode 100644 index 000000000..a24a4fc9b --- /dev/null +++ b/conf/Other/gnss-sdr_GPS_L1_monitor.conf @@ -0,0 +1,89 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=2000000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/tmp/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat +SignalSource.item_type=ishort +SignalSource.sampling_frequency=4000000 +SignalSource.freq=1575420000 +SignalSource.samples=0 +SignalSource.enable_throttle_control=true + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Ishort_To_Complex + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Pass_Through +InputFilter.item_type=gr_complex + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Direct_Resampler +Resampler.sample_freq_in=4000000 +Resampler.sample_freq_out=2000000 +Resampler.item_type=gr_complex + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=3 +Channels.in_acquisition=1 +Channel.signal=1C +Channel0.satellite=1 +Channel1.satellite=11 +Channel2.satellite=17 + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.threshold=0.008 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=4.0; + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.averaging_depth=100 +PVT.flag_averaging=true +PVT.output_rate_ms=10 +PVT.display_rate_ms=500 +PVT.enable_monitor=true +PVT.monitor_client_addresses=127.0.0.1 +PVT.monitor_udp_port=1234 + +;######### MONITOR CONFIG ############ +Monitor.enable_monitor=true +Monitor.decimation_factor=1 +Monitor.client_addresses=127.0.0.1 +Monitor.udp_port=1233 + +;######### ACQUISITION MONITOR CONFIG ############ +AcquisitionMonitor.enable_monitor=true +AcquisitionMonitor.decimation_factor=1 +AcquisitionMonitor.client_addresses=127.0.0.1 +AcquisitionMonitor.udp_port=1231 + +;######### TRACKING MONITOR CONFIG ############ +TrackingMonitor.enable_monitor=true +TrackingMonitor.decimation_factor=1 +TrackingMonitor.client_addresses=127.0.0.1 +TrackingMonitor.udp_port=1232 diff --git a/conf/Other/gnss-sdr_GPS_L1_nsr_twobit_packed.conf b/conf/Other/gnss-sdr_GPS_L1_nsr_twobit_packed.conf new file mode 100644 index 000000000..01209aefb --- /dev/null +++ b/conf/Other/gnss-sdr_GPS_L1_nsr_twobit_packed.conf @@ -0,0 +1,154 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; Sample configuration file for IFEN SX-NSR software receiver front-end +; https://www.ifen.com/products/sx3-gnss-software-receiver/ +; This sample configuration is able to process directly .sream binary files +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2560000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=false +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Two_Bit_Packed_File_Signal_Source +SignalSource.filename=/datalogger/signals/ifen/E1L1_FE0_Band0.stream ; <- PUT YOUR FILE HERE +SignalSource.item_type=byte +; big_endian_items : not needed for byte inputs +; If the input were 'short' then this can either be big endian or little +; endian. If it is big endian then the second byte should be output +; first in each short. +; SignalSource.big_endian_items=false +; big_endian_bytes: true if the most signficiant two bits in the byte +; are the first two to be output. +SignalSource.big_endian_bytes=false +; sample_type: one of 'real' 'iq' or 'qi' +; Data is either real or complex. +; if the data is complex there are two conventions for sample ordering: +; 1) Real first : 'iq' +; 2) Imaginary first: 'qi' +; This setting specifies which of the three cases holds for this data file +SignalSource.sample_type=real +SignalSource.sampling_frequency=20480000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through +DataTypeAdapter.item_type=float + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat +InputFilter.input_item_type=float +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=20480000 +InputFilter.IF=5499998.47412109 +InputFilter.decimation_factor=8 + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat +Resampler.item_type=gr_complex + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels.in_acquisition=1 +Channel.signal=1C + + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.sampled_ms=1 +Acquisition_1C.pfa=0.015 +;Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=45.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.dump=false +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=10 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=true diff --git a/conf/Other/gnss-sdr_GPS_L1_pulse_blanking_gr_complex.conf b/conf/Other/gnss-sdr_GPS_L1_pulse_blanking_gr_complex.conf new file mode 100644 index 000000000..b0d592f84 --- /dev/null +++ b/conf/Other/gnss-sdr_GPS_L1_pulse_blanking_gr_complex.conf @@ -0,0 +1,111 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2000000 + +;######### CONTROL_THREAD CONFIG ############ +ControlThread.wait_for_flowgraph=false + +;######### SUPL RRLP GPS assistance configuration ##### +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.nokia.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=File_Signal_Source +SignalSource.filename=/home/javier/signals/signal_source_int.dat +SignalSource.item_type=gr_complex +SignalSource.sampling_frequency=2000000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=dump.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Pulse_Blanking_Filter +InputFilter.Pfa=0.001 +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels.in_acquisition=8 +Channel.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=2.5 +;Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.extend_correlation_ms=10 +Tracking_1C.pll_bw_hz=35; +Tracking_1C.pll_bw_narrow_hz=30; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.dll_bw_narrow_hz=1.5; +Tracking_1C.fll_bw_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.dump=true +Tracking_1C.dump_filename=../data/epl_tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=true +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=1 +PVT.display_rate_ms=100 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false diff --git a/conf/Other/gnss-sdr_GPS_L1_two_bits_cpx.conf b/conf/Other/gnss-sdr_GPS_L1_two_bits_cpx.conf new file mode 100644 index 000000000..67c4d60e1 --- /dev/null +++ b/conf/Other/gnss-sdr_GPS_L1_two_bits_cpx.conf @@ -0,0 +1,138 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=3200000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=false +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Two_Bit_Cpx_File_Signal_Source +SignalSource.filename=/datalogger/captures/ajith/test1_two_cpx_live.dat ; <- PUT YOUR FILE HERE +SignalSource.item_type=byte +SignalSource.sampling_frequency=19200000 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.enable_throttle_control=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through +DataTypeAdapter.item_type=gr_complex + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=19200000 +InputFilter.IF=4024000 +InputFilter.decimation_factor=6 +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat +Resampler.item_type=gr_complex + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=6 +Channels.in_acquisition=1 +Channel.signal=1C + + +;######### GPS ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition_Fine_Doppler +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +;Acquisition_1C.pfa=0.0001 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_min=-10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.max_dwells=15 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GPS CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=1.5; +Tracking_1C.order=3; +Tracking_1C.dump=true +Tracking_1C.dump_filename=./tracking_ch + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=10 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false diff --git a/conf/Other/gnss-sdr_GPS_L1_udp_with_monitor.conf b/conf/Other/gnss-sdr_GPS_L1_udp_with_monitor.conf new file mode 100644 index 000000000..9b7b18b94 --- /dev/null +++ b/conf/Other/gnss-sdr_GPS_L1_udp_with_monitor.conf @@ -0,0 +1,82 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [Sps] +GNSS-SDR.internal_fs_sps=4000000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Custom_UDP_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.origin_address=127.0.0.1 +SignalSource.capture_device=lo +SignalSource.port=1230 +;SignalSource.payload_bytes=1472 # Not used! Size is retrieved from UDP Packet +SignalSource.sample_type=cfloat +SignalSource.IQ_swap=true +SignalSource.RF_channels=1 +SignalSource.channels_in_udp=1 +SignalSource.dump=false +SignalSource.dump_filename=./signal_source.dat + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=3 +Channels.in_acquisition=1 +Channel.signal=1C +Channel0.satellite=1 +Channel1.satellite=11 +Channel2.satellite=17 + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.threshold=0.008 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=4.0; + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.averaging_depth=100 +PVT.flag_averaging=true +PVT.output_rate_ms=10 +PVT.display_rate_ms=500 +PVT.enable_monitor=true +PVT.monitor_client_addresses=127.0.0.1 +PVT.monitor_udp_port=1234 + +;######### MONITOR CONFIG ############ +Monitor.enable_monitor=true +Monitor.decimation_factor=1 +Monitor.client_addresses=127.0.0.1 +Monitor.udp_port=1233 + +;######### ACQUISITION MONITOR CONFIG ############ +AcquisitionMonitor.enable_monitor=true +AcquisitionMonitor.decimation_factor=1 +AcquisitionMonitor.client_addresses=127.0.0.1 +AcquisitionMonitor.udp_port=1231 + +;######### TRACKING MONITOR CONFIG ############ +TrackingMonitor.enable_monitor=true +TrackingMonitor.decimation_factor=1 +TrackingMonitor.client_addresses=127.0.0.1 +TrackingMonitor.udp_port=1232 \ No newline at end of file diff --git a/conf/RealTime_input/gnss-sdr_GPS_L1_2ch_fmcomms2_realtime.conf b/conf/RealTime_input/gnss-sdr_GPS_L1_2ch_fmcomms2_realtime.conf new file mode 100644 index 000000000..3fc5c22d2 --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_GPS_L1_2ch_fmcomms2_realtime.conf @@ -0,0 +1,115 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [Sps]. +GNSS-SDR.internal_fs_sps=7000000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Fmcomms2_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.device_address=192.168.0.4 +SignalSource.sampling_frequency=7000000 +SignalSource.freq=1575420000 +SignalSource.bandwidth=4000000 +SignalSource.RF_channels=2 +SignalSource.rx1_enable=true +SignalSource.rx2_enable=true +SignalSource.gain_mode_rx1=slow_attack +SignalSource.gain_mode_rx2=slow_attack +SignalSource.rf_port_select=A_BALANCED +SignalSource.gain_rx1=64 +SignalSource.gain_rx2=64 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.enable_dds_lo=false +SignalSource.freq_rf_tx_hz=1260000000 +SignalSource.freq_dds_tx_hz=1000 +SignalSource.scale_dds_dbfs=0.0 +SignalSource.phase_dds_deg=0.0 +SignalSource.tx_attenuation_db=0.0 + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner0.implementation=Pass_Through +SignalConditioner1.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels.in_acquisition=1 + +;# CHANNEL CONNECTION +Channel0.RF_channel_ID=0 +Channel0.signal=1C +Channel1.RF_channel_ID=0 +Channel1.signal=1C +Channel2.RF_channel_ID=0 +Channel2.signal=1C +Channel3.RF_channel_ID=0 +Channel3.signal=1C +Channel4.RF_channel_ID=1 +Channel4.signal=1C +Channel5.RF_channel_ID=1 +Channel5.signal=1C +Channel6.RF_channel_ID=1 +Channel6.signal=1C +Channel7.RF_channel_ID=1 +Channel7.signal=1C + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.threshold=2.5 +Acquisition_1C.blocking=true +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ +Tracking_1C.pll_bw_hz=35.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.early_late_space_chips=0.5; + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false diff --git a/conf/RealTime_input/gnss-sdr_GPS_L1_LimeSDR.conf b/conf/RealTime_input/gnss-sdr_GPS_L1_LimeSDR.conf new file mode 100644 index 000000000..c2a6b5019 --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_GPS_L1_LimeSDR.conf @@ -0,0 +1,129 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2021 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=5000000 +GNSS-SDR.use_acquisition_resampler=true + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Limesdr_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.sampling_frequency=5000000 +SignalSource.freq=1575420000 +SignalSource.gain=50 ; 0-73 dB no AGC in LimeSDR +; SignalSource.analog_bw ; if not set, defaults to sample_rate/2 +; SignalSource.digital_bw ; if not set, defaults to 0 (disabled filter) +; SignalSource.limesdr_serial ; if not set, its automatic +SignalSource.antenna=2 ; None(0), LNAH(1), LNAL(2), LNAW(3), AUTO(255) +SignalSource.ext_clock_MHz=0 ; 0 -> internal clock +SignalSource.limechannel_mode=0 ; A(0), B(1) or (A+B) MIMO(2) +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=./captured_signal.dat + +SignalConditioner.implementation=Signal_Conditioner +DataTypeAdapter.implementation=Pass_Through +InputFilter.implementation=Pulse_Blanking_Filter ; <- Required in some locations +InputFilter.pfa=0.001 +InputFilter.segments_est=2500 +Resampler.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=7 +Channels_1B.count=0 +Channels.in_acquisition=1 +Channel.signal=1C + + +;######### GPS L1 ACQUISITION CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=5000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + +;######### GALILEO E1 ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +Acquisition_1B.pfa=0.01 +Acquisition_1B.blocking=false +Acquisition_1B.doppler_max=5000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + + +;######### GPS L1 TRACKING CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ +Tracking_1C.pll_bw_hz=45.0; +Tracking_1C.dll_bw_hz=4.0; +Tracking_1C.pll_bw_narrow_hz=5.0; +Tracking_1C.dll_bw_narrow_hz=0.75; +Tracking_1C.extend_correlation_symbols=1; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.early_late_space_narrow_chips=0.5 + +;######### GALILEO E1 TRACKING CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=15.0; +Tracking_1B.dll_bw_hz=0.75; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.5; +Tracking_1B.pll_bw_narrow_hz=5.0 +Tracking_1B.dll_bw_narrow_hz=0.5 +Tracking_1B.extend_correlation_symbols=1 +Tracking_1B.track_pilot=true +Tracking_1B.enable_fll_pull_in=true; +; Tracking_1B.pull_in_time_s=60 +Tracking_1B.enable_fll_steady_state=false +Tracking_1B.fll_bw_hz=10 +Tracking_1B.dump=false +Tracking_1B.dump_filename=tracking_ch_ + + +;######### TELEMETRY DECODER GPS L1 CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + +;######### TELEMETRY DECODER Galileo E1 CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.enable_rx_clock_correction=false +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.rinexobs_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.dump=false +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 diff --git a/conf/RealTime_input/gnss-sdr_GPS_L1_USRP_X300_realtime.conf b/conf/RealTime_input/gnss-sdr_GPS_L1_USRP_X300_realtime.conf new file mode 100644 index 000000000..f0ab33656 --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_GPS_L1_USRP_X300_realtime.conf @@ -0,0 +1,157 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; Configuration file for using USRP X300 as a RF front-end for GPS L1 signals. +; Set SignalSource.device_address to the IP address of your device +; and run: +; gnss-sdr --config_file=/path/to/gnss-sdr_GPS_L1_USRP_X300_realtime_new.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=UHD_Signal_Source +SignalSource.device_address=192.168.40.2 ; <- PUT THE IP ADDRESS OF YOUR USRP HERE +SignalSource.item_type=cshort +SignalSource.sampling_frequency=4000000 +SignalSource.freq=1575420000 +SignalSource.gain=40 +SignalSource.subdevice=A:0 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through +DataTypeAdapter.item_type=cshort + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Fir_Filter +InputFilter.input_item_type=cshort +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=11 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.48 +InputFilter.band2_begin=0.52 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=4000000 +InputFilter.IF=0 +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.item_type=gr_complex +Resampler.sample_freq_in=4000000 +Resampler.sample_freq_out=4000000 +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels_1B.count=0 +Channels.in_acquisition=1 +Channel.signal=1C + +;Channel0.signal=1C +;Channel1.signal=1C +;Channel2.signal=1C +;Channel3.signal=1C +;Channel4.signal=1C +;Channel5.signal=1C +;Channel6.signal=1C +;Channel7.signal=1C +;Channel8.signal=1C +;Channel9.signal=1C +;Channel10.signal=1C +;Channel11.signal=1C + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=0.01 +;Acquisition_1C.pfa=0.00001 +Acquisition_1C.doppler_max=8000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=30.0; +Tracking_1C.dll_bw_hz=4.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/RealTime_input/gnss-sdr_GPS_L1_USRP_realtime.conf b/conf/RealTime_input/gnss-sdr_GPS_L1_USRP_realtime.conf new file mode 100644 index 000000000..04afb9a6c --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_GPS_L1_USRP_realtime.conf @@ -0,0 +1,118 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; Configuration file for using USRP 1 as a RF front-end for GPS L1 signals. +; Run: +; gnss-sdr --config_file=/path/to/gnss-sdr_GPS_L1_USRP_realtime.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2000000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=UHD_Signal_Source +;SignalSource.device_address=192.168.40.2 ; <- PUT THE IP ADDRESS OF YOUR USRP HERE +SignalSource.item_type=gr_complex +SignalSource.sampling_frequency=2000000 +SignalSource.freq=1575420000 +SignalSource.gain=60 +SignalSource.subdevice=A:0 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Pass_Through + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=6 +Channels_1B.count=0 +Channels.in_acquisition=1 + + +;#signal: +;# "1C" GPS L1 C/A +;# "1B" GALILEO E1 B (I/NAV OS/CS/SoL) +;# "1G" GLONASS L1 C/A +;# "2S" GPS L2 L2C (M) +;# "5X" GALILEO E5a I+Q +;# "L5" GPS L5 + +Channel.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=0.01 +;Acquisition_1C.pfa=0.0001 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=30.0; +Tracking_1C.dll_bw_hz=4.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +;#implementation: Position Velocity and Time (PVT) implementation: +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/RealTime_input/gnss-sdr_GPS_L1_bladeRF.conf b/conf/RealTime_input/gnss-sdr_GPS_L1_bladeRF.conf new file mode 100644 index 000000000..e751730de --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_GPS_L1_bladeRF.conf @@ -0,0 +1,109 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=2000000 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Osmosdr_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.sampling_frequency=2000000 +SignalSource.freq=1575420000 +;# RF Gain: LNA Gain {0, 3, 6} +SignalSource.gain=6 +;# IF Gain: N/A +SignalSource.rf_gain=40 +;# BB Gain: RX VGA1 + VGA2 [5, 60] +SignalSource.if_gain=48 +SignalSource.AGC_enabled=false +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.osmosdr_args=bladerf=0 ; This line enables the bladeRF +SignalSource.dump=false +SignalSource.dump_filename=./signal_source.dat + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.decimation_factor=1 +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.85 +InputFilter.band2_begin=0.9 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels.in_acquisition=1 +Channel.signal=1C + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition_Fine_Doppler +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=0.015 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.max_dwells=15 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + +;######### PVT CONFIG ############ +;PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=Single +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.iono_model=Broadcast +PVT.trop_model=Saastamoinen +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.rtcm_tcp_port=2101 +PVT.rtcm_MT1019_rate_ms=5000 +PVT.rtcm_MT1077_rate_ms=1000 +PVT.rinex_version=2 diff --git a/conf/RealTime_input/gnss-sdr_GPS_L1_fmcomms2_realtime.conf b/conf/RealTime_input/gnss-sdr_GPS_L1_fmcomms2_realtime.conf new file mode 100644 index 000000000..df763f64e --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_GPS_L1_fmcomms2_realtime.conf @@ -0,0 +1,134 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +GNSS-SDR.internal_fs_sps=2000000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=false +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Fmcomms2_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.device_address=10.42.0.196 +SignalSource.sampling_frequency=2000000 +SignalSource.freq=1575420000 +SignalSource.bandwidth=2000000 +SignalSource.rx1_enable=true +SignalSource.gain_mode_rx1=manual +SignalSource.rf_port_select=A_BALANCED +SignalSource.gain_rx1=64 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=2000000 +InputFilter.IF=0; IF deviation due to front-end LO inaccuracies [Hz] + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=5 +Channels.in_acquisition=1 +Channel.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition_Fine_Doppler +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=0.015 +;Acquisition_1C.pfa=0.0001 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.max_dwells=15 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false diff --git a/conf/RealTime_input/gnss-sdr_GPS_L1_plutosdr_realtime.conf b/conf/RealTime_input/gnss-sdr_GPS_L1_plutosdr_realtime.conf new file mode 100644 index 000000000..e140810d2 --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_GPS_L1_plutosdr_realtime.conf @@ -0,0 +1,145 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [sps]. +;FOR USE GNSS-SDR WITH RTLSDR DONGLES USER MUST SET THE CALIBRATED SAMPLE RATE HERE +; i.e. using front-end-cal as reported here: https://www.researchgate.net/publication/257137427_Turning_a_Television_into_a_GNSS_Receiver +GNSS-SDR.internal_fs_sps=4000000 +GNSS-SDR.use_acquisition_resampler=true + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=false +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Plutosdr_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.device_address=192.168.2.1 +SignalSource.sampling_frequency=4000000 +SignalSource.freq=1575420000 +SignalSource.bandwidth=2000000 +SignalSource.gain_mode=slow_attack +SignalSource.gain=30 +SignalSource.samples=0 +SignalSource.buffer_size=65000 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=./capture.dat + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=8 +Channels_1B.count=0 +Channels.in_acquisition=1 +Channel.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.use_CFAR_algorithm=false; +Acquisition_1C.threshold=2.6 +Acquisition_1C.doppler_max=50000 +Acquisition_1C.doppler_step=250 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + +;######### GALILEO ACQUISITION CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.threshold=2.5 +Acquisition_1B.use_CFAR_algorithm=false +Acquisition_1B.blocking=false +Acquisition_1B.doppler_max=6000 +Acquisition_1B.doppler_step=125 +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ +Tracking_1C.pll_bw_hz=35.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.enable_fll_pull_in=true; +Tracking_1C.fll_bw_hz=10 +Tracking_1C.pll_bw_narrow_hz=5.0; +Tracking_1C.dll_bw_narrow_hz=0.75; +Tracking_1C.extend_correlation_symbols=1; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.early_late_space_narrow_chips=0.5 + +;######### TRACKING GALILEO CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=15.0; +Tracking_1B.dll_bw_hz=0.75; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.5; +Tracking_1B.pll_bw_narrow_hz=5.0 +Tracking_1B.dll_bw_narrow_hz=0.5 +Tracking_1B.extend_correlation_symbols=1 +Tracking_1B.track_pilot=true +Tracking_1B.enable_fll_pull_in=true; +;Tracking_1B.pull_in_time_s=60 +Tracking_1B.enable_fll_steady_state=false +Tracking_1B.fll_bw_hz=10 +Tracking_1B.dump=false +Tracking_1B.dump_filename=tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.enable_rx_clock_correction=false +PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.rinexobs_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.dump=false +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 diff --git a/conf/RealTime_input/gnss-sdr_GPS_L1_rtl_tcp_realtime.conf b/conf/RealTime_input/gnss-sdr_GPS_L1_rtl_tcp_realtime.conf new file mode 100644 index 000000000..370931cca --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_GPS_L1_rtl_tcp_realtime.conf @@ -0,0 +1,151 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +;FOR USE GNSS-SDR WITH RTLSDR DONGLES USER MUST SET THE CALIBRATED SAMPLE RATE HERE +; i.e. using front-end-cal as reported here: https://www.researchgate.net/publication/257137427_Turning_a_Television_into_a_GNSS_Receiver +; i.e. using front-end-cal as reported here: https://www.researchgate.net/publication/257137427_Turning_a_Television_into_a_GNSS_Receiver +GNSS-SDR.internal_fs_sps=1200000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=false +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +;#implementation +SignalSource.implementation=RtlTcp_Signal_Source +SignalSource.sampling_frequency=1200000 +SignalSource.freq=1575420000 +SignalSource.gain=40 +SignalSource.rf_gain=40 +SignalSource.if_gain=30 +SignalSource.AGC_enabled = false +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat +SignalSource.address=127.0.0.1 +SignalSource.port=1234 +SignalSource.swap_iq=false + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 + +;#The following options are used only in Freq_Xlating_Fir_Filter implementation. +;#InputFilter.IF is the intermediate frequency (in Hz) shifted down to zero Hz +;FOR USE GNSS-SDR WITH RTLSDR DONGLES USER MUST SET THE CALIBRATED SAMPLE RATE HERE +; i.e. using front-end-cal as reported here: https://www.researchgate.net/publication/257137427_Turning_a_Television_into_a_GNSS_Receiver +InputFilter.sampling_frequency=1200000 +InputFilter.IF=80558 + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=4 +Channels.in_acquisition=1 +Channel.signal=1C + + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition_Fine_Doppler +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=0.015 +;Acquisition_1C.pfa=0.0001 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_min=-10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.max_dwells=15 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +;#implementation: +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +;#implementation: Position Velocity and Time (PVT) implementation: +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=true +PVT.dump_filename=./PVT diff --git a/conf/RealTime_input/gnss-sdr_GPS_L1_rtlsdr_realtime.conf b/conf/RealTime_input/gnss-sdr_GPS_L1_rtlsdr_realtime.conf new file mode 100644 index 000000000..8994bb3f3 --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_GPS_L1_rtlsdr_realtime.conf @@ -0,0 +1,153 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +;FOR USE GNSS-SDR WITH RTLSDR DONGLES USER MUST SET THE CALIBRATED SAMPLE RATE HERE +; i.e. using front-end-cal as reported here: https://www.researchgate.net/publication/257137427_Turning_a_Television_into_a_GNSS_Receiver +GNSS-SDR.internal_fs_sps=1999898 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=false +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=Osmosdr_Signal_Source +SignalSource.item_type=gr_complex +; FOR USE GNSS-SDR WITH RTLSDR DONGLES USER MUST SET THE CALIBRATED SAMPLE RATE HERE +; i.e. using front-end-cal as reported here: https://www.researchgate.net/publication/257137427_Turning_a_Television_into_a_GNSS_Receiver +SignalSource.sampling_frequency=2000000 +SignalSource.freq=1575420000 +SignalSource.gain=40 +SignalSource.rf_gain=40 +SignalSource.if_gain=30 +SignalSource.AGC_enabled = false +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat + +;# Please note that the new RTL-SDR Blog V3 dongles ship a < 1 PPM +;# temperature compensated oscillator (TCXO), which is well suited for GNSS +;# signal processing, and a 4.5 V powered bias-tee to feed an active antenna. +;# Whether the bias-tee is turned off before reception depends on which version +;# of gr-osmosdr was used when compiling GNSS-SDR. With an old version +;# (for example, v0.1.4-8), the utility rtl_biast may be used to switch the +;# bias-tee, and then call gnss-sdr. +;# See https://github.com/rtlsdrblog/rtl_biast +;# After reception the bias-tee is switched off automatically by the program. +;# With newer versions of gr-osmosdr (>= 0.1.4-13), the bias-tee can be +;# activated by uncommenting the following line: +;SignalSource.osmosdr_args=rtl,bias=1 + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +;FOR USE GNSS-SDR WITH RTLSDR DONGLES USER MUST SET THE CALIBRATED SAMPLE RATE HERE +; i.e. using front-end-cal as reported here: https://www.researchgate.net/publication/257137427_Turning_a_Television_into_a_GNSS_Receiver +InputFilter.sampling_frequency=1999898 +InputFilter.IF=80558 ; IF deviation due to front-end LO inaccuracies [Hz] + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=4 +Channels.in_acquisition=1 +Channel.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition_Fine_Doppler +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=0.015 +;Acquisition_1C.pfa=0.0001 +Acquisition_1C.doppler_max=10000 +Acquisition_1C.doppler_min=-10000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.max_dwells=15 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=2.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.dump=false +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 diff --git a/conf/RealTime_input/gnss-sdr_GPS_L2C_USRP1_realtime.conf b/conf/RealTime_input/gnss-sdr_GPS_L2C_USRP1_realtime.conf new file mode 100644 index 000000000..cffb6f9b0 --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_GPS_L2C_USRP1_realtime.conf @@ -0,0 +1,156 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; Configuration file for using USRP1 as a RF front-end for GPS L2C signals +; Run: +; gnss-sdr --config_file=/path/to/gnss-sdr_GPS_L2C_USRP1_realtime.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=2000000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=UHD_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.sampling_frequency=2000000 +SignalSource.freq=1227600000 +SignalSource.gain=60 +SignalSource.subdevice=A:0 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through +DataTypeAdapter.item_type=gr_complex + + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter.implementation=Freq_Xlating_Fir_Filter +InputFilter.input_item_type=gr_complex +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=5 +InputFilter.number_of_bands=2 +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.45 +InputFilter.band2_begin=0.55 +InputFilter.band2_end=1.0 +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=20000000 +InputFilter.IF=-1600000 +InputFilter.decimation_factor=1 +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat +Resampler.item_type=gr_complex +Resampler.sample_freq_in=2000000 +Resampler.sample_freq_out=2000000 + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_2S.count=1 +Channels.in_acquisition=1 + +Channel.signal=2S + +Channel0.signal=2S +Channel1.signal=2S +Channel2.signal=2S +Channel3.signal=2S +Channel4.signal=2S +Channel5.signal=2S +Channel6.signal=2S +Channel7.signal=2S +;Channel8.signal=2S +;Channel9.signal=2S +;Channel10.signal=2S +;Channel11.signal=2S + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_2S.implementation=GPS_L2_M_PCPS_Acquisition +Acquisition_2S.item_type=gr_complex +Acquisition_2S.pfa=0.013 +;Acquisition_2S.pfa=0.001 +Acquisition_2S.doppler_max=10000 +Acquisition_2S.doppler_step=100 +Acquisition_2S.max_dwells=1 +Acquisition_2S.dump=false +Acquisition_2S.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_2S.implementation=GPS_L2_M_DLL_PLL_Tracking +Tracking_2S.item_type=gr_complex +Tracking_2S.pll_bw_hz=1.5; +Tracking_2S.dll_bw_hz=0.3; +Tracking_2S.order=3; +Tracking_2S.early_late_space_chips=0.5; +Tracking_2S.dump=true +Tracking_2S.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_2S.implementation=GPS_L2C_Telemetry_Decoder +TelemetryDecoder_2S.dump=false + + +;######### OBSERVABLES CONFIG ############. +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.dump_filename=./PVT +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false diff --git a/conf/RealTime_input/gnss-sdr_GPS_L2C_USRP_X300_realtime.conf b/conf/RealTime_input/gnss-sdr_GPS_L2C_USRP_X300_realtime.conf new file mode 100644 index 000000000..a221b7169 --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_GPS_L2C_USRP_X300_realtime.conf @@ -0,0 +1,162 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; Configuration file for using USRP X300 as a RF front-end for GPS L2C signals +; Set SignalSource.device_address to the IP address of your device +; and run: +; gnss-sdr --config_file=/path/to/gnss-sdr_GPS_L2C_USRP_X300_realtime.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_gps_enabled=false +GNSS-SDR.SUPL_read_gps_assistance_xml=true +GNSS-SDR.SUPL_gps_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_gps_ephemeris_port=7275 +GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com +GNSS-SDR.SUPL_gps_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=UHD_Signal_Source +SignalSource.device_address=192.168.50.2 ; <- PUT THE IP ADDRESS OF YOUR USRP HERE +SignalSource.item_type=cshort +SignalSource.sampling_frequency=4000000 +SignalSource.freq=1227600000 +;### Options: internal, external, or MIMO +SignalSource.clock_source=internal +SignalSource.gain=35 +SignalSource.subdevice=A:0 +SignalSource.samples=0 +SignalSource.repeat=false +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Signal_Conditioner + +;######### DATA_TYPE_ADAPTER CONFIG ############ +DataTypeAdapter.implementation=Pass_Through +DataTypeAdapter.item_type=cshort + +;######### INPUT_FILTER CONFIG ############ +InputFilter.implementation=Fir_Filter +InputFilter.input_item_type=cshort +InputFilter.output_item_type=gr_complex +InputFilter.taps_item_type=float +InputFilter.number_of_taps=11 +InputFilter.number_of_bands=2 + +InputFilter.band1_begin=0.0 +InputFilter.band1_end=0.48 +InputFilter.band2_begin=0.52 +InputFilter.band2_end=1.0 + +InputFilter.ampl1_begin=1.0 +InputFilter.ampl1_end=1.0 +InputFilter.ampl2_begin=0.0 +InputFilter.ampl2_end=0.0 + +InputFilter.band1_error=1.0 +InputFilter.band2_error=1.0 + +InputFilter.filter_type=bandpass +InputFilter.grid_density=16 +InputFilter.sampling_frequency=4000000 +InputFilter.IF=0 + +InputFilter.dump=false +InputFilter.dump_filename=../data/input_filter.dat + +;######### RESAMPLER CONFIG ############ +Resampler.implementation=Pass_Through +Resampler.dump=false +Resampler.dump_filename=../data/resampler.dat +Resampler.item_type=gr_complex +Resampler.sample_freq_in=4000000 +Resampler.sample_freq_out=4000000 + + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_2S.count=1 +Channels.in_acquisition=1 + +Channel.signal=2S + +Channel0.signal=2S +Channel1.signal=2S +Channel2.signal=2S +Channel3.signal=2S +Channel4.signal=2S +Channel5.signal=2S +Channel6.signal=2S +Channel7.signal=2S +;Channel8.signal=2S +;Channel9.signal=2S +;Channel10.signal=2S +;Channel11.signal=2S + +;######### ACQUISITION GLOBAL CONFIG ############ + +;# GPS L2C M +Acquisition_2S.implementation=GPS_L2_M_PCPS_Acquisition +Acquisition_2S.item_type=gr_complex +Acquisition_2S.pfa=0.015 +;Acquisition_2S.pfa=0.001 +Acquisition_2S.doppler_max=5000 +Acquisition_2S.doppler_min=-5000 +Acquisition_2S.doppler_step=60 +Acquisition_2S.max_dwells=1 +Acquisition_2S.dump=false +Acquisition_2S.dump_filename=./acq_dump.dat + + +Tracking_2S.implementation=GPS_L2_M_DLL_PLL_Tracking +Tracking_2S.item_type=gr_complex +Tracking_2S.pll_bw_hz=2.0; +Tracking_2S.dll_bw_hz=0.25; +Tracking_2S.order=2; +Tracking_2S.early_late_space_chips=0.5; +Tracking_2S.dump=true +Tracking_2S.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_2S.implementation=GPS_L2C_Telemetry_Decoder +TelemetryDecoder_2S.dump=true + + +;######### OBSERVABLES CONFIG ############. +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=false +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/RealTime_input/gnss-sdr_Galileo_E1_USRP_X300_realtime.conf b/conf/RealTime_input/gnss-sdr_Galileo_E1_USRP_X300_realtime.conf new file mode 100644 index 000000000..b49801d10 --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_Galileo_E1_USRP_X300_realtime.conf @@ -0,0 +1,93 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; Configuration file for using USRP X300 as a RF front-end for Galileo E1 signals. +; Set SignalSource.device_address to the IP address of your device +; and run: +; gnss-sdr --config_file=/path/to/gnss-sdr_Galileo_E1_USRP_X300_realtime.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 +GNSS-SDR.Galileo_banned_prns=14,18 + + +;######### SIGNAL_SOURCE CONFIG ############ +SignalSource.implementation=UHD_Signal_Source +SignalSource.item_type=gr_complex +SignalSource.device_address=192.168.40.2 ; <- PUT THE IP ADDRESS OF YOUR USRP HERE +SignalSource.sampling_frequency=4000000 +SignalSource.freq=1575420000 +SignalSource.gain=50 +SignalSource.subdevice=A:0 +SignalSource.samples=0 +SignalSource.dump=false +SignalSource.dump_filename=../data/signal_source.dat + + +;######### SIGNAL_CONDITIONER CONFIG ############ +SignalConditioner.implementation=Pass_Through + + +;######### CHANNELS GLOBAL CONFIG ###### +Channels_1B.count=4 +Channels.in_acquisition=1 +Channel.signal=1B + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition +Acquisition_1B.item_type=gr_complex +Acquisition_1B.coherent_integration_time_ms=4 +;Acquisition_1B.threshold=1 +Acquisition_1B.pfa=0.000008 +Acquisition_1B.doppler_max=6000 +Acquisition_1B.doppler_step=250 +Acquisition_1B.cboc=false +Acquisition_1B.dump=false +Acquisition_1B.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking +Tracking_1B.item_type=gr_complex +Tracking_1B.pll_bw_hz=20.0; +Tracking_1B.dll_bw_hz=2.0; +Tracking_1B.order=3; +Tracking_1B.early_late_space_chips=0.15; +Tracking_1B.very_early_late_space_chips=0.6; +Tracking_1B.dump=false +Tracking_1B.dump_filename=../data/veml_tracking_ch_ + + +;######### TELEMETRY DECODER CONFIG ############ +TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder +TelemetryDecoder_1B.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100; +PVT.display_rate_ms=500; +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea +PVT.flag_nmea_tty_port=true +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT diff --git a/conf/RealTime_input/gnss-sdr_multichannel_GPS_L1_USRP_X300_realtime.conf b/conf/RealTime_input/gnss-sdr_multichannel_GPS_L1_USRP_X300_realtime.conf new file mode 100644 index 000000000..61f18e09f --- /dev/null +++ b/conf/RealTime_input/gnss-sdr_multichannel_GPS_L1_USRP_X300_realtime.conf @@ -0,0 +1,161 @@ +; This is a GNSS-SDR configuration file +; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/ +; SPDX-License-Identifier: GPL-3.0-or-later +; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors) + +; You can define your own receiver and invoke it by doing +; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf +; + +[GNSS-SDR] + +;######### GLOBAL OPTIONS ################## +;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second]. +GNSS-SDR.internal_fs_sps=4000000 + + +;######### SUPL RRLP GPS assistance configuration ##### +; Check https://www.mcc-mnc.com/ +; On Android: https://play.google.com/store/apps/details?id=net.its_here.cellidinfo&hl=en +GNSS-SDR.SUPL_1C_enabled=false +GNSS-SDR.SUPL_read_1C_assistance_xml=true +GNSS-SDR.SUPL_1C_ephemeris_server=supl.google.com +GNSS-SDR.SUPL_1C_ephemeris_port=7275 +GNSS-SDR.SUPL_1C_acquisition_server=supl.google.com +GNSS-SDR.SUPL_1C_acquisition_port=7275 +GNSS-SDR.SUPL_MCC=244 +GNSS-SDR.SUPL_MNC=5 +GNSS-SDR.SUPL_LAC=0x59e2 +GNSS-SDR.SUPL_CI=0x31b0 + +;######### SIGNAL_SOURCE CONFIG ############ +;#implementation +SignalSource.implementation=UHD_Signal_Source +SignalSource.device_address=192.168.40.2 ; <- PUT THE IP ADDRESS OF YOUR USRP HERE +SignalSource.item_type=gr_complex +SignalSource.RF_channels=2 +SignalSource.sampling_frequency=4000000 +SignalSource.subdevice=A:0 B:0 + +;######### RF Channels specific settings ###### +;## RF CHANNEL 0 ## +SignalSource.freq0=1575420000 +SignalSource.gain0=50 +SignalSource.samples0=0 + +;## RF CHANNEL 1 ## +SignalSource.freq1=1575420000 +SignalSource.gain1=50 +SignalSource.samples1=0 + + +;######### SIGNAL_CONDITIONER 0 CONFIG ############ +SignalConditioner0.implementation=Pass_Through + +;######### DATA_TYPE_ADAPTER 0 CONFIG ############ +DataTypeAdapter0.implementation=Pass_Through +DataTypeAdapter0.item_type=gr_complex + +;######### INPUT_FILTER 0 CONFIG ############ +InputFilter0.implementation=Pass_Through +InputFilter0.dump=false +InputFilter0.dump_filename=../data/input_filter.dat +InputFilter0.input_item_type=gr_complex +InputFilter0.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 0 ############ +Resampler0.implementation=Pass_Through + + +;######### SIGNAL_CONDITIONER 1 CONFIG ############ +SignalConditioner1.implementation=Pass_Through + + +;######### INPUT_FILTER 1 CONFIG ############ +InputFilter1.implementation=Pass_Through +InputFilter1.dump=false +InputFilter1.dump_filename=../data/input_filter.dat +InputFilter1.input_item_type=gr_complex +InputFilter1.output_item_type=gr_complex + +;######### RESAMPLER CONFIG 1 ############ +Resampler1.implementation=Pass_Through + +;######### CHANNELS GLOBAL CONFIG ############ +Channels_1C.count=4 + +Channels.in_acquisition=1 + +;#signal: +;# "1C" GPS L1 C/A +;# "1B" GALILEO E1 B (I/NAV OS/CS/SoL) +;# "1G" GLONASS L1 C/A +;# "2S" GPS L2 L2C (M) +;# "5X" GALILEO E5a I+Q +;# "L5" GPS L5 + +;# CHANNEL CONNECTION +Channel0.RF_channel_ID=0 +Channel1.RF_channel_ID=1 +Channel2.RF_channel_ID=0 +Channel3.RF_channel_ID=1 + + +;#signal: +Channel0.signal=1C +Channel1.signal=1C +Channel2.signal=1C +Channel3.signal=1C + + +;######### ACQUISITION GLOBAL CONFIG ############ +Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition +Acquisition_1C.item_type=gr_complex +Acquisition_1C.coherent_integration_time_ms=1 +Acquisition_1C.threshold=0.01 +;Acquisition_1C.pfa=0.01 +Acquisition_1C.doppler_max=8000 +Acquisition_1C.doppler_step=500 +Acquisition_1C.bit_transition_flag=false +Acquisition_1C.max_dwells=1 +Acquisition_1C.dump=false +Acquisition_1C.dump_filename=./acq_dump.dat + + +;######### TRACKING GLOBAL CONFIG ############ +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking +Tracking_1C.item_type=gr_complex +Tracking_1C.pll_bw_hz=40.0; +Tracking_1C.dll_bw_hz=4.0; +Tracking_1C.order=3; +Tracking_1C.early_late_space_chips=0.5; +Tracking_1C.dump=false +Tracking_1C.dump_filename=./tracking_ch_ + + +;######### TELEMETRY DECODER GPS CONFIG ############ +TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder +TelemetryDecoder_1C.dump=false + + +;######### OBSERVABLES CONFIG ############ +Observables.implementation=Hybrid_Observables +Observables.dump=false +Observables.dump_filename=./observables.dat + + +;######### PVT CONFIG ############ +PVT.implementation=RTKLIB_PVT +PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic +PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX +PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad +PVT.output_rate_ms=100 +PVT.display_rate_ms=500 +PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea; +PVT.flag_nmea_tty_port=false; +PVT.nmea_dump_devname=/dev/pts/4 +PVT.flag_rtcm_server=true +PVT.flag_rtcm_tty_port=false +PVT.rtcm_dump_devname=/dev/pts/1 +PVT.dump=false +PVT.dump_filename=./PVT