Write public interface first, then private members in class definitions

This commit is contained in:
Carles Fernandez 2019-07-01 23:44:42 +02:00
parent f1022385b0
commit 018cde8953
No known key found for this signature in database
GPG Key ID: 4C583C52B0C3877D
52 changed files with 757 additions and 719 deletions

View File

@ -77,6 +77,57 @@ rtklib_pvt_gs_sptr rtklib_make_pvt_gs(uint32_t nchannels,
*/ */
class rtklib_pvt_gs : public gr::sync_block class rtklib_pvt_gs : public gr::sync_block
{ {
public:
~rtklib_pvt_gs(); //!< Default destructor
/*!
* \brief Get latest set of GPS ephemeris from PVT block
*/
std::map<int, Gps_Ephemeris> get_gps_ephemeris_map() const;
/*!
* \brief Get latest set of GPS almanac from PVT block
*/
std::map<int, Gps_Almanac> get_gps_almanac_map() const;
/*!
* \brief Get latest set of Galileo ephemeris from PVT block
*/
std::map<int, Galileo_Ephemeris> get_galileo_ephemeris_map() const;
/*!
* \brief Get latest set of Galileo almanac from PVT block
*/
std::map<int, Galileo_Almanac> get_galileo_almanac_map() const;
/*!
* \brief Get latest set of BeiDou DNAV ephemeris from PVT block
*/
std::map<int, Beidou_Dnav_Ephemeris> get_beidou_dnav_ephemeris_map() const;
/*!
* \brief Get latest set of BeiDou DNAV almanac from PVT block
*/
std::map<int, Beidou_Dnav_Almanac> get_beidou_dnav_almanac_map() const;
/*!
* \brief Clear all ephemeris information and the almanacs for GPS and Galileo
*/
void clear_ephemeris();
/*!
* \brief Get the latest Position WGS84 [deg], Ground Velocity, Course over Ground, and UTC Time, if available
*/
bool 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) const;
int work(int noutput_items, gr_vector_const_void_star& input_items,
gr_vector_void_star& output_items); //!< PVT Signal Processing
private: private:
friend rtklib_pvt_gs_sptr rtklib_make_pvt_gs(uint32_t nchannels, friend rtklib_pvt_gs_sptr rtklib_make_pvt_gs(uint32_t nchannels,
const Pvt_Conf& conf_, const Pvt_Conf& conf_,
@ -169,57 +220,6 @@ private:
bool d_show_local_time_zone; bool d_show_local_time_zone;
std::string d_local_time_str; std::string d_local_time_str;
boost::posix_time::time_duration d_utc_diff_time; boost::posix_time::time_duration d_utc_diff_time;
public:
~rtklib_pvt_gs(); //!< Default destructor
/*!
* \brief Get latest set of GPS ephemeris from PVT block
*/
std::map<int, Gps_Ephemeris> get_gps_ephemeris_map() const;
/*!
* \brief Get latest set of GPS almanac from PVT block
*/
std::map<int, Gps_Almanac> get_gps_almanac_map() const;
/*!
* \brief Get latest set of Galileo ephemeris from PVT block
*/
std::map<int, Galileo_Ephemeris> get_galileo_ephemeris_map() const;
/*!
* \brief Get latest set of Galileo almanac from PVT block
*/
std::map<int, Galileo_Almanac> get_galileo_almanac_map() const;
/*!
* \brief Get latest set of BeiDou DNAV ephemeris from PVT block
*/
std::map<int, Beidou_Dnav_Ephemeris> get_beidou_dnav_ephemeris_map() const;
/*!
* \brief Get latest set of BeiDou DNAV almanac from PVT block
*/
std::map<int, Beidou_Dnav_Almanac> get_beidou_dnav_almanac_map() const;
/*!
* \brief Clear all ephemeris information and the almanacs for GPS and Galileo
*/
void clear_ephemeris();
/*!
* \brief Get the latest Position WGS84 [deg], Ground Velocity, Course over Ground, and UTC Time, if available
*/
bool 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) const;
int work(int noutput_items, gr_vector_const_void_star& input_items,
gr_vector_void_star& output_items); //!< PVT Signal Processing
}; };
#endif #endif

View File

@ -47,18 +47,18 @@ class Pvt_Solution;
*/ */
class GeoJSON_Printer class GeoJSON_Printer
{ {
private:
std::ofstream geojson_file;
bool first_pos;
std::string filename_;
std::string geojson_base_path;
public: public:
GeoJSON_Printer(const std::string& base_path = "."); GeoJSON_Printer(const std::string& base_path = ".");
~GeoJSON_Printer(); ~GeoJSON_Printer();
bool set_headers(const std::string& filename, bool time_tag_name = true); bool set_headers(const std::string& filename, bool time_tag_name = true);
bool print_position(const std::shared_ptr<Pvt_Solution>& position, bool print_average_values); bool print_position(const std::shared_ptr<Pvt_Solution>& position, bool print_average_values);
bool close_file(); bool close_file();
private:
std::ofstream geojson_file;
bool first_pos;
std::string filename_;
std::string geojson_base_path;
}; };
#endif #endif

View File

@ -47,19 +47,19 @@ class Rtklib_Solver;
*/ */
class Gpx_Printer class Gpx_Printer
{ {
private:
std::ofstream gpx_file;
bool positions_printed;
std::string gpx_filename;
std::string indent;
std::string gpx_base_path;
public: public:
Gpx_Printer(const std::string& base_path = "."); Gpx_Printer(const std::string& base_path = ".");
~Gpx_Printer(); ~Gpx_Printer();
bool set_headers(const std::string& filename, bool time_tag_name = true); bool set_headers(const std::string& filename, bool time_tag_name = true);
bool print_position(const std::shared_ptr<Rtklib_Solver>& position, bool print_average_values); bool print_position(const std::shared_ptr<Rtklib_Solver>& position, bool print_average_values);
bool close_file(); bool close_file();
private:
std::ofstream gpx_file;
bool positions_printed;
std::string gpx_filename;
std::string indent;
std::string gpx_base_path;
}; };
#endif #endif

View File

@ -48,14 +48,6 @@
*/ */
class Hybrid_Ls_Pvt : public Ls_Pvt class Hybrid_Ls_Pvt : public Ls_Pvt
{ {
private:
int count_valid_position;
bool d_flag_dump_enabled;
std::string d_dump_filename;
std::ofstream d_dump_file;
int d_nchannels; // Number of available channels for positioning
double d_galileo_current_time;
public: public:
Hybrid_Ls_Pvt(int nchannels, std::string dump_filename, bool flag_dump_to_file); Hybrid_Ls_Pvt(int nchannels, std::string dump_filename, bool flag_dump_to_file);
~Hybrid_Ls_Pvt(); ~Hybrid_Ls_Pvt();
@ -75,6 +67,14 @@ public:
Gps_CNAV_Iono gps_cnav_iono; Gps_CNAV_Iono gps_cnav_iono;
Gps_CNAV_Utc_Model gps_cnav_utc_model; Gps_CNAV_Utc_Model gps_cnav_utc_model;
private:
int count_valid_position;
bool d_flag_dump_enabled;
std::string d_dump_filename;
std::ofstream d_dump_file;
int d_nchannels; // Number of available channels for positioning
double d_galileo_current_time;
}; };
#endif #endif

View File

@ -46,6 +46,13 @@ class Rtklib_Solver;
*/ */
class Kml_Printer class Kml_Printer
{ {
public:
Kml_Printer(const std::string& base_path = std::string("."));
~Kml_Printer();
bool set_headers(const std::string& filename, bool time_tag_name = true);
bool print_position(const std::shared_ptr<Rtklib_Solver>& position, bool print_average_values);
bool close_file();
private: private:
std::ofstream kml_file; std::ofstream kml_file;
std::ofstream tmp_file; std::ofstream tmp_file;
@ -55,13 +62,6 @@ private:
std::string tmp_file_str; std::string tmp_file_str;
unsigned int point_id; unsigned int point_id;
std::string indent; std::string indent;
public:
Kml_Printer(const std::string& base_path = std::string("."));
~Kml_Printer();
bool set_headers(const std::string& filename, bool time_tag_name = true);
bool print_position(const std::shared_ptr<Rtklib_Solver>& position, bool print_average_values);
bool close_file();
}; };
#endif #endif

View File

@ -41,12 +41,6 @@
*/ */
class Ls_Pvt : public Pvt_Solution class Ls_Pvt : public Pvt_Solution
{ {
private:
/*!
* \brief Computes the Lorentz inner product between two vectors
*/
double lorentz(const arma::vec& x, const arma::vec& y);
public: public:
Ls_Pvt(); Ls_Pvt();
@ -59,6 +53,12 @@ public:
* \brief Computes the Weighted Least Squares position solution * \brief Computes the Weighted Least Squares position solution
*/ */
arma::vec leastSquarePos(const arma::mat& satpos, const arma::vec& obs, const arma::vec& w_vec); arma::vec leastSquarePos(const arma::mat& satpos, const arma::vec& obs, const arma::vec& w_vec);
private:
/*!
* \brief Computes the Lorentz inner product between two vectors
*/
double lorentz(const arma::vec& x, const arma::vec& y);
}; };
#endif #endif

View File

@ -44,32 +44,6 @@
*/ */
class Pvt_Solution class Pvt_Solution
{ {
private:
double d_rx_dt_s; // RX time offset [s]
double d_latitude_d; // RX position Latitude WGS84 [deg]
double d_longitude_d; // RX position Longitude WGS84 [deg]
double d_height_m; // RX position height WGS84 [m]
double d_speed_over_ground_m_s; // RX speed over ground [m/s]
double d_course_over_ground_d; // RX course over ground [deg]
double d_avg_latitude_d; // Averaged latitude in degrees
double d_avg_longitude_d; // Averaged longitude in degrees
double d_avg_height_m; // Averaged height [m]
bool b_valid_position;
std::deque<double> d_hist_latitude_d;
std::deque<double> d_hist_longitude_d;
std::deque<double> d_hist_height_m;
bool d_flag_averaging;
int d_averaging_depth; // Length of averaging window
arma::vec d_rx_pos;
boost::posix_time::ptime d_position_UTC_time;
int d_valid_observations;
public: public:
Pvt_Solution(); Pvt_Solution();
@ -111,46 +85,73 @@ public:
arma::vec rotateSatellite(double traveltime, const arma::vec &X_sat); arma::vec rotateSatellite(double traveltime, const arma::vec &X_sat);
/*! /*!
* \brief Conversion of Cartesian coordinates (X,Y,Z) to geographical * \brief Conversion of Cartesian coordinates (X,Y,Z) to geographical
* coordinates (d_latitude_d, d_longitude_d, d_height_m) on a selected reference ellipsoid. * coordinates (d_latitude_d, d_longitude_d, d_height_m) on a selected reference ellipsoid.
* *
* \param[in] X [m] Cartesian coordinate * \param[in] X [m] Cartesian coordinate
* \param[in] Y [m] Cartesian coordinate * \param[in] Y [m] Cartesian coordinate
* \param[in] Z [m] Cartesian coordinate * \param[in] Z [m] Cartesian coordinate
* \param[in] elipsoid_selection. Choices of Reference Ellipsoid for Geographical Coordinates: * \param[in] elipsoid_selection. Choices of Reference Ellipsoid for Geographical Coordinates:
* 0 - International Ellipsoid 1924. * 0 - International Ellipsoid 1924.
* 1 - International Ellipsoid 1967. * 1 - International Ellipsoid 1967.
* 2 - World Geodetic System 1972. * 2 - World Geodetic System 1972.
* 3 - Geodetic Reference System 1980. * 3 - Geodetic Reference System 1980.
* 4 - World Geodetic System 1984. * 4 - World Geodetic System 1984.
* *
*/ */
int cart2geo(double X, double Y, double Z, int elipsoid_selection); int cart2geo(double X, double Y, double Z, int elipsoid_selection);
/*! /*!
* \brief Tropospheric correction * \brief Tropospheric correction
* *
* \param[in] sinel - sin of elevation angle of satellite * \param[in] sinel - sin of elevation angle of satellite
* \param[in] hsta_km - height of station in km * \param[in] hsta_km - height of station in km
* \param[in] p_mb - atmospheric pressure in mb at height hp_km * \param[in] p_mb - atmospheric pressure in mb at height hp_km
* \param[in] t_kel - surface temperature in degrees Kelvin at height htkel_km * \param[in] t_kel - surface temperature in degrees Kelvin at height htkel_km
* \param[in] hum - humidity in % at height hhum_km * \param[in] hum - humidity in % at height hhum_km
* \param[in] hp_km - height of pressure measurement in km * \param[in] hp_km - height of pressure measurement in km
* \param[in] htkel_km - height of temperature measurement in km * \param[in] htkel_km - height of temperature measurement in km
* \param[in] hhum_km - height of humidity measurement in km * \param[in] hhum_km - height of humidity measurement in km
* *
* \param[out] ddr_m - range correction (meters) * \param[out] ddr_m - range correction (meters)
* *
* *
* Reference: * Reference:
* Goad, C.C. & Goodman, L. (1974) A Modified Hopfield Tropospheric * Goad, C.C. & Goodman, L. (1974) A Modified Hopfield Tropospheric
* Refraction Correction Model. Paper presented at the * Refraction Correction Model. Paper presented at the
* American Geophysical Union Annual Fall Meeting, San * American Geophysical Union Annual Fall Meeting, San
* Francisco, December 12-17 * Francisco, December 12-17
* *
* Translated to C++ by Carles Fernandez from a Matlab implementation by Kai Borre * Translated to C++ by Carles Fernandez from a Matlab implementation by Kai Borre
*/ */
int tropo(double *ddr_m, double sinel, double hsta_km, double p_mb, double t_kel, double hum, double hp_km, double htkel_km, double hhum_km); int tropo(double *ddr_m, double sinel, double hsta_km, double p_mb, double t_kel, double hum, double hp_km, double htkel_km, double hhum_km);
private:
double d_rx_dt_s; // RX time offset [s]
double d_latitude_d; // RX position Latitude WGS84 [deg]
double d_longitude_d; // RX position Longitude WGS84 [deg]
double d_height_m; // RX position height WGS84 [m]
double d_speed_over_ground_m_s; // RX speed over ground [m/s]
double d_course_over_ground_d; // RX course over ground [deg]
double d_avg_latitude_d; // Averaged latitude in degrees
double d_avg_longitude_d; // Averaged longitude in degrees
double d_avg_height_m; // Averaged height [m]
bool b_valid_position;
std::deque<double> d_hist_latitude_d;
std::deque<double> d_hist_longitude_d;
std::deque<double> d_hist_height_m;
bool d_flag_averaging;
int d_averaging_depth; // Length of averaging window
arma::vec d_rx_pos;
boost::posix_time::ptime d_position_UTC_time;
int d_valid_observations;
}; };
#endif #endif

View File

@ -88,18 +88,6 @@
*/ */
class Rtklib_Solver : public Pvt_Solution class Rtklib_Solver : public Pvt_Solution
{ {
private:
rtk_t rtk_;
std::string d_dump_filename;
std::ofstream d_dump_file;
bool save_matfile();
bool d_flag_dump_enabled;
bool d_flag_dump_mat_enabled;
int d_nchannels; // Number of available channels for positioning
std::array<double, 4> dop_;
Monitor_Pvt monitor_pvt;
public: public:
Rtklib_Solver(int nchannels, std::string dump_filename, bool flag_dump_to_file, bool flag_dump_to_mat, const rtk_t& rtk); Rtklib_Solver(int nchannels, std::string dump_filename, bool flag_dump_to_file, bool flag_dump_to_mat, const rtk_t& rtk);
~Rtklib_Solver(); ~Rtklib_Solver();
@ -139,6 +127,17 @@ public:
std::map<int, Beidou_Dnav_Almanac> beidou_dnav_almanac_map; std::map<int, Beidou_Dnav_Almanac> beidou_dnav_almanac_map;
int count_valid_position; int count_valid_position;
private:
rtk_t rtk_;
std::string d_dump_filename;
std::ofstream d_dump_file;
bool save_matfile();
bool d_flag_dump_enabled;
bool d_flag_dump_mat_enabled;
int d_nchannels; // Number of available channels for positioning
std::array<double, 4> dop_;
Monitor_Pvt monitor_pvt;
}; };
#endif #endif

View File

@ -47,15 +47,15 @@ channel_msg_receiver_cc_sptr channel_msg_receiver_make_cc(std::shared_ptr<Channe
*/ */
class channel_msg_receiver_cc : public gr::block class channel_msg_receiver_cc : public gr::block
{ {
public:
~channel_msg_receiver_cc(); //!< Default destructor
private: private:
std::shared_ptr<ChannelFsm> d_channel_fsm; std::shared_ptr<ChannelFsm> d_channel_fsm;
bool d_repeat; // todo: change FSM to include repeat value bool d_repeat; // todo: change FSM to include repeat value
friend channel_msg_receiver_cc_sptr channel_msg_receiver_make_cc(std::shared_ptr<ChannelFsm> channel_fsm, bool repeat); friend channel_msg_receiver_cc_sptr channel_msg_receiver_make_cc(std::shared_ptr<ChannelFsm> channel_fsm, bool repeat);
void msg_handler_events(pmt::pmt_t msg); void msg_handler_events(pmt::pmt_t msg);
channel_msg_receiver_cc(std::shared_ptr<ChannelFsm> channel_fsm, bool repeat); channel_msg_receiver_cc(std::shared_ptr<ChannelFsm> channel_fsm, bool repeat);
public:
~channel_msg_receiver_cc(); //!< Default destructor
}; };
#endif #endif

View File

@ -47,15 +47,14 @@ interleaved_byte_to_complex_byte_sptr make_interleaved_byte_to_complex_byte();
*/ */
class interleaved_byte_to_complex_byte : public gr::sync_decimator class interleaved_byte_to_complex_byte : public gr::sync_decimator
{ {
private:
friend interleaved_byte_to_complex_byte_sptr make_interleaved_byte_to_complex_byte();
public: public:
interleaved_byte_to_complex_byte();
int work(int noutput_items, int work(int noutput_items,
gr_vector_const_void_star &input_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
private:
friend interleaved_byte_to_complex_byte_sptr make_interleaved_byte_to_complex_byte();
interleaved_byte_to_complex_byte();
}; };
#endif #endif

View File

@ -46,15 +46,14 @@ interleaved_byte_to_complex_short_sptr make_interleaved_byte_to_complex_short();
*/ */
class interleaved_byte_to_complex_short : public gr::sync_decimator class interleaved_byte_to_complex_short : public gr::sync_decimator
{ {
private:
friend interleaved_byte_to_complex_short_sptr make_interleaved_byte_to_complex_short();
public: public:
interleaved_byte_to_complex_short();
int work(int noutput_items, int work(int noutput_items,
gr_vector_const_void_star &input_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
private:
friend interleaved_byte_to_complex_short_sptr make_interleaved_byte_to_complex_short();
interleaved_byte_to_complex_short();
}; };
#endif #endif // GNSS_SDR_INTERLEAVED_BYTE_TO_COMPLEX_SHORT_H_

View File

@ -46,15 +46,14 @@ interleaved_short_to_complex_short_sptr make_interleaved_short_to_complex_short(
*/ */
class interleaved_short_to_complex_short : public gr::sync_decimator class interleaved_short_to_complex_short : public gr::sync_decimator
{ {
private:
friend interleaved_short_to_complex_short_sptr make_interleaved_short_to_complex_short();
public: public:
interleaved_short_to_complex_short();
int work(int noutput_items, int work(int noutput_items,
gr_vector_const_void_star &input_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
private:
friend interleaved_short_to_complex_short_sptr make_interleaved_short_to_complex_short();
interleaved_short_to_complex_short();
}; };
#endif #endif // GNSS_SDR_INTERLEAVED_SHORT_TO_COMPLEX_SHORT_H_

View File

@ -43,17 +43,15 @@ beamformer_sptr make_beamformer();
*/ */
class beamformer : public gr::sync_block class beamformer : public gr::sync_block
{ {
private:
friend beamformer_sptr
make_beamformer_sptr();
gr_complex *weight_vector;
public: public:
beamformer(); beamformer();
~beamformer(); ~beamformer();
int work(int noutput_items, gr_vector_const_void_star &input_items, int work(int noutput_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
private:
friend beamformer_sptr make_beamformer_sptr();
gr_complex *weight_vector;
}; };
#endif #endif

View File

@ -47,9 +47,19 @@ notch_sptr make_notch_filter(float pfa, float p_c_factor,
/*! /*!
* \brief This class implements a real-time software-defined multi state notch filter * \brief This class implements a real-time software-defined multi state notch filter
*/ */
class Notch : public gr::block class Notch : public gr::block
{ {
public:
Notch(float pfa, float p_c_factor, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset);
~Notch();
void forecast(int noutput_items, gr_vector_int &ninput_items_required);
int general_work(int noutput_items, gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
private: private:
float pfa; float pfa;
float noise_pow_est; float noise_pow_est;
@ -67,17 +77,6 @@ private:
float *angle_; float *angle_;
float *power_spect; float *power_spect;
std::unique_ptr<gr::fft::fft_complex> d_fft; std::unique_ptr<gr::fft::fft_complex> d_fft;
public:
Notch(float pfa, float p_c_factor, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset);
~Notch();
void forecast(int noutput_items, gr_vector_int &ninput_items_required);
int general_work(int noutput_items, gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
}; };
#endif //GNSS_SDR_NOTCH_H_ #endif // GNSS_SDR_NOTCH_H_

View File

@ -46,9 +46,19 @@ notch_lite_sptr make_notch_filter_lite(float p_c_factor, float pfa, int32_t leng
/*! /*!
* \brief This class implements a real-time software-defined multi state notch filter light version * \brief This class implements a real-time software-defined multi state notch filter light version
*/ */
class NotchLite : public gr::block class NotchLite : public gr::block
{ {
public:
NotchLite(float p_c_factor, float pfa, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset, int32_t n_segments_coeff);
~NotchLite();
void forecast(int noutput_items, gr_vector_int &ninput_items_required);
int general_work(int noutput_items, gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
private: private:
int32_t length_; int32_t length_;
int32_t n_segments; int32_t n_segments;
@ -70,17 +80,6 @@ private:
float angle2; float angle2;
float *power_spect; float *power_spect;
std::unique_ptr<gr::fft::fft_complex> d_fft; std::unique_ptr<gr::fft::fft_complex> d_fft;
public:
NotchLite(float p_c_factor, float pfa, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset, int32_t n_segments_coeff);
~NotchLite();
void forecast(int noutput_items, gr_vector_int &ninput_items_required);
int general_work(int noutput_items, gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
}; };
#endif //GNSS_SDR_NOTCH_LITE_H_ #endif // GNSS_SDR_NOTCH_LITE_H_

View File

@ -44,6 +44,16 @@ pulse_blanking_cc_sptr make_pulse_blanking_cc(float pfa, int32_t length_, int32_
class pulse_blanking_cc : public gr::block class pulse_blanking_cc : public gr::block
{ {
public:
pulse_blanking_cc(float pfa, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset);
~pulse_blanking_cc();
void forecast(int noutput_items, gr_vector_int &ninput_items_required);
int general_work(int noutput_items __attribute__((unused)), gr_vector_int &ninput_items __attribute__((unused)),
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
private: private:
int32_t length_; int32_t length_;
int32_t n_segments; int32_t n_segments;
@ -55,16 +65,6 @@ private:
float thres_; float thres_;
float pfa; float pfa;
gr_complex *zeros_; gr_complex *zeros_;
public:
pulse_blanking_cc(float pfa, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset);
~pulse_blanking_cc();
int general_work(int noutput_items __attribute__((unused)), gr_vector_int &ninput_items __attribute__((unused)),
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
void forecast(int noutput_items, gr_vector_int &ninput_items_required);
}; };
#endif #endif // GNSS_SDR_PULSE_BLANKING_H_

View File

@ -38,9 +38,10 @@
class direct_resampler_conditioner_cb; class direct_resampler_conditioner_cb;
using direct_resampler_conditioner_cb_sptr = boost::shared_ptr<direct_resampler_conditioner_cb>; using direct_resampler_conditioner_cb_sptr = boost::shared_ptr<direct_resampler_conditioner_cb>;
direct_resampler_conditioner_cb_sptr direct_resampler_conditioner_cb_sptr direct_resampler_make_conditioner_cb(
direct_resampler_make_conditioner_cb(double sample_freq_in, double sample_freq_in,
double sample_freq_out); double sample_freq_out);
/*! /*!
* \brief This class implements a direct resampler conditioner for std::complex<signed char> * \brief This class implements a direct resampler conditioner for std::complex<signed char>
* *
@ -48,20 +49,6 @@ direct_resampler_make_conditioner_cb(double sample_freq_in,
*/ */
class direct_resampler_conditioner_cb : public gr::block class direct_resampler_conditioner_cb : public gr::block
{ {
private:
friend direct_resampler_conditioner_cb_sptr
direct_resampler_make_conditioner_cb(double sample_freq_in,
double sample_freq_out);
double d_sample_freq_in;
double d_sample_freq_out;
uint32_t d_phase;
uint32_t d_lphase;
uint32_t d_phase_step;
direct_resampler_conditioner_cb(double sample_freq_in,
double sample_freq_out);
public: public:
~direct_resampler_conditioner_cb(); ~direct_resampler_conditioner_cb();
@ -80,6 +67,21 @@ public:
int general_work(int noutput_items, gr_vector_int &ninput_items, int general_work(int noutput_items, gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
private:
friend direct_resampler_conditioner_cb_sptr direct_resampler_make_conditioner_cb(
double sample_freq_in,
double sample_freq_out);
direct_resampler_conditioner_cb(
double sample_freq_in,
double sample_freq_out);
double d_sample_freq_in;
double d_sample_freq_out;
uint32_t d_phase;
uint32_t d_lphase;
uint32_t d_phase_step;
}; };
#endif /* GNSS_SDR_DIRECT_RESAMPLER_CONDITIONER_CS_H */ #endif /* GNSS_SDR_DIRECT_RESAMPLER_CONDITIONER_CS_H */

View File

@ -43,9 +43,11 @@
#include <volk/volk.h> #include <volk/volk.h>
class direct_resampler_conditioner_cc; class direct_resampler_conditioner_cc;
using direct_resampler_conditioner_cc_sptr = boost::shared_ptr<direct_resampler_conditioner_cc>; using direct_resampler_conditioner_cc_sptr = boost::shared_ptr<direct_resampler_conditioner_cc>;
direct_resampler_conditioner_cc_sptr
direct_resampler_make_conditioner_cc(double sample_freq_in, direct_resampler_conditioner_cc_sptr direct_resampler_make_conditioner_cc(
double sample_freq_in,
double sample_freq_out); double sample_freq_out);
/*! /*!
@ -55,18 +57,6 @@ direct_resampler_make_conditioner_cc(double sample_freq_in,
*/ */
class direct_resampler_conditioner_cc : public gr::block class direct_resampler_conditioner_cc : public gr::block
{ {
private:
friend direct_resampler_conditioner_cc_sptr
direct_resampler_make_conditioner_cc(double sample_freq_in,
double sample_freq_out);
double d_sample_freq_in; //! Specifies the sampling frequency of the input signal
double d_sample_freq_out; //! Specifies the sampling frequency of the output signal
uint32_t d_phase;
uint32_t d_lphase;
uint32_t d_phase_step;
direct_resampler_conditioner_cc(double sample_freq_in,
double sample_freq_out);
public: public:
~direct_resampler_conditioner_cc(); ~direct_resampler_conditioner_cc();
inline unsigned int sample_freq_in() const inline unsigned int sample_freq_in() const
@ -84,6 +74,21 @@ public:
int general_work(int noutput_items, gr_vector_int &ninput_items, int general_work(int noutput_items, gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
private:
friend direct_resampler_conditioner_cc_sptr direct_resampler_make_conditioner_cc(
double sample_freq_in,
double sample_freq_out);
direct_resampler_conditioner_cc(
double sample_freq_in,
double sample_freq_out);
double d_sample_freq_in; // Sampling frequency of the input signal
double d_sample_freq_out; // Sampling frequency of the output signal
uint32_t d_phase;
uint32_t d_lphase;
uint32_t d_phase_step;
}; };
#endif /* GNSS_SDR_DIRECT_RESAMPLER_CONDITIONER_CC_H */ #endif /* GNSS_SDR_DIRECT_RESAMPLER_CONDITIONER_CC_H */

View File

@ -38,9 +38,10 @@
class direct_resampler_conditioner_cs; class direct_resampler_conditioner_cs;
using direct_resampler_conditioner_cs_sptr = boost::shared_ptr<direct_resampler_conditioner_cs>; using direct_resampler_conditioner_cs_sptr = boost::shared_ptr<direct_resampler_conditioner_cs>;
direct_resampler_conditioner_cs_sptr direct_resampler_conditioner_cs_sptr direct_resampler_make_conditioner_cs(
direct_resampler_make_conditioner_cs(double sample_freq_in, double sample_freq_in,
double sample_freq_out); double sample_freq_out);
/*! /*!
* \brief This class implements a direct resampler conditioner for std::complex<short> * \brief This class implements a direct resampler conditioner for std::complex<short>
* *
@ -48,20 +49,6 @@ direct_resampler_make_conditioner_cs(double sample_freq_in,
*/ */
class direct_resampler_conditioner_cs : public gr::block class direct_resampler_conditioner_cs : public gr::block
{ {
private:
friend direct_resampler_conditioner_cs_sptr
direct_resampler_make_conditioner_cs(double sample_freq_in,
double sample_freq_out);
double d_sample_freq_in;
double d_sample_freq_out;
uint32_t d_phase;
uint32_t d_lphase;
uint32_t d_phase_step;
direct_resampler_conditioner_cs(double sample_freq_in,
double sample_freq_out);
public: public:
~direct_resampler_conditioner_cs(); ~direct_resampler_conditioner_cs();
@ -80,6 +67,21 @@ public:
int general_work(int noutput_items, gr_vector_int &ninput_items, int general_work(int noutput_items, gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
private:
friend direct_resampler_conditioner_cs_sptr direct_resampler_make_conditioner_cs(
double sample_freq_in,
double sample_freq_out);
direct_resampler_conditioner_cs(
double sample_freq_in,
double sample_freq_out);
double d_sample_freq_in;
double d_sample_freq_out;
uint32_t d_phase;
uint32_t d_lphase;
uint32_t d_phase_step;
}; };
#endif /* GNSS_SDR_DIRECT_RESAMPLER_CONDITIONER_CS_H */ #endif /* GNSS_SDR_DIRECT_RESAMPLER_CONDITIONER_CS_H */

View File

@ -60,11 +60,19 @@ using signal_generator_c_sptr = boost::shared_ptr<signal_generator_c>;
* constructor is private. signal_make_generator_c is the public * constructor is private. signal_make_generator_c is the public
* interface for creating new instances. * interface for creating new instances.
*/ */
signal_generator_c_sptr signal_generator_c_sptr signal_make_generator_c(
signal_make_generator_c(std::vector<std::string> signal1, std::vector<std::string> system, const std::vector<unsigned int> &PRN, std::vector<std::string> signal1,
const std::vector<float> &CN0_dB, const std::vector<float> &doppler_Hz, std::vector<std::string> system,
const std::vector<unsigned int> &delay_chips, const std::vector<unsigned int> &delay_sec, bool data_flag, bool noise_flag, const std::vector<unsigned int> &PRN,
unsigned int fs_in, unsigned int vector_length, float BW_BB); const std::vector<float> &CN0_dB,
const std::vector<float> &doppler_Hz,
const std::vector<unsigned int> &delay_chips,
const std::vector<unsigned int> &delay_sec,
bool data_flag,
bool noise_flag,
unsigned int fs_in,
unsigned int vector_length,
float BW_BB);
/*! /*!
* \brief This class generates synthesized GNSS signal. * \brief This class generates synthesized GNSS signal.
@ -74,23 +82,46 @@ signal_make_generator_c(std::vector<std::string> signal1, std::vector<std::strin
*/ */
class signal_generator_c : public gr::block class signal_generator_c : public gr::block
{ {
public:
~signal_generator_c(); // public destructor
// Where all the action really happens
int general_work(int noutput_items,
gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
private: private:
// The friend declaration allows gen_source to friend signal_generator_c_sptr signal_make_generator_c(
// access the private constructor. std::vector<std::string> signal1,
std::vector<std::string> system,
const std::vector<unsigned int> &PRN,
const std::vector<float> &CN0_dB,
const std::vector<float> &doppler_Hz,
const std::vector<unsigned int> &delay_chips,
const std::vector<unsigned int> &delay_sec,
bool data_flag,
bool noise_flag,
unsigned int fs_in,
unsigned int vector_length,
float BW_BB);
/* Create the signal_generator_c object*/ signal_generator_c(
friend signal_generator_c_sptr std::vector<std::string> signal1,
signal_make_generator_c(std::vector<std::string> signal1, std::vector<std::string> system, const std::vector<unsigned int> &PRN, std::vector<std::string> system,
const std::vector<float> &CN0_dB, const std::vector<float> &doppler_Hz, const std::vector<unsigned int> &PRN,
const std::vector<unsigned int> &delay_chips, const std::vector<unsigned int> &delay_sec, bool data_flag, bool noise_flag, std::vector<float> CN0_dB,
unsigned int fs_in, unsigned int vector_length, float BW_BB); std::vector<float> doppler_Hz,
std::vector<unsigned int> delay_chips,
signal_generator_c(std::vector<std::string> signal1, std::vector<std::string> system, const std::vector<unsigned int> &PRN, std::vector<unsigned int> delay_sec,
std::vector<float> CN0_dB, std::vector<float> doppler_Hz, bool data_flag,
std::vector<unsigned int> delay_chips, std::vector<unsigned int> delay_sec, bool data_flag, bool noise_flag, bool noise_flag,
unsigned int fs_in, unsigned int vector_length, float BW_BB); unsigned int fs_in,
unsigned int vector_length,
float BW_BB);
void init(); void init();
void generate_codes(); void generate_codes();
std::vector<std::string> signal_; std::vector<std::string> signal_;
@ -106,7 +137,6 @@ private:
unsigned int num_sats_; unsigned int num_sats_;
unsigned int vector_length_; unsigned int vector_length_;
float BW_BB_; float BW_BB_;
std::vector<unsigned int> samples_per_code_; std::vector<unsigned int> samples_per_code_;
std::vector<unsigned int> num_of_codes_per_vector_; std::vector<unsigned int> num_of_codes_per_vector_;
std::vector<unsigned int> data_bit_duration_ms_; std::vector<unsigned int> data_bit_duration_ms_;
@ -116,28 +146,15 @@ private:
std::vector<signed int> current_data_bit_int_; std::vector<signed int> current_data_bit_int_;
std::vector<signed int> data_modulation_; std::vector<signed int> data_modulation_;
std::vector<signed int> pilot_modulation_; std::vector<signed int> pilot_modulation_;
boost::scoped_array<gr_complex *> sampled_code_data_; boost::scoped_array<gr_complex *> sampled_code_data_;
boost::scoped_array<gr_complex *> sampled_code_pilot_; boost::scoped_array<gr_complex *> sampled_code_pilot_;
//gr::random *random_;
gr_complex *complex_phase_; gr_complex *complex_phase_;
unsigned int work_counter_; unsigned int work_counter_;
std::random_device r; std::random_device r;
std::default_random_engine e1; std::default_random_engine e1;
std::default_random_engine e2; std::default_random_engine e2;
std::uniform_int_distribution<int> uniform_dist; std::uniform_int_distribution<int> uniform_dist;
std::normal_distribution<float> normal_dist; std::normal_distribution<float> normal_dist;
public:
~signal_generator_c(); // public destructor
// Where all the action really happens
int general_work(int noutput_items,
gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
}; };
#endif /* GNSS_SDR_SIGNAL_GENERATOR_C_H */ #endif /* GNSS_SDR_SIGNAL_GENERATOR_C_H */

View File

@ -45,42 +45,6 @@
class Gr_Complex_Ip_Packet_Source : virtual public gr::sync_block class Gr_Complex_Ip_Packet_Source : virtual public gr::sync_block
{ {
private:
boost::mutex d_mutex;
pcap_t *descr; //ethernet pcap device descriptor
char *fifo_buff;
int fifo_read_ptr;
int fifo_write_ptr;
int fifo_items;
int d_sock_raw;
int d_udp_port;
struct sockaddr_in si_me;
std::string d_src_device;
std::string d_origin_address;
int d_udp_payload_size;
bool d_fifo_full;
int d_n_baseband_channels;
int d_wire_sample_type;
int d_bytes_per_sample;
size_t d_item_size;
bool d_IQ_swap;
boost::thread *d_pcap_thread;
/*!
* \brief
* Opens the ethernet device using libpcap raw capture mode
* If any of these fail, the fuction retuns the error and exits.
*/
bool open();
void demux_samples(gr_vector_void_star output_items, int num_samples_readed);
void my_pcap_loop_thread(pcap_t *pcap_handle);
void pcap_callback(u_char *args, const struct pcap_pkthdr *pkthdr, const u_char *packet);
static void static_pcap_callback(u_char *args, const struct pcap_pkthdr *pkthdr, const u_char *packet);
public: public:
typedef boost::shared_ptr<Gr_Complex_Ip_Packet_Source> sptr; typedef boost::shared_ptr<Gr_Complex_Ip_Packet_Source> sptr;
static sptr make(std::string src_device, static sptr make(std::string src_device,
@ -101,15 +65,46 @@ public:
bool IQ_swap_); bool IQ_swap_);
~Gr_Complex_Ip_Packet_Source(); ~Gr_Complex_Ip_Packet_Source();
// Called by gnuradio to enable drivers, etc for i/o devices.
bool start();
// Called by gnuradio to disable drivers, etc for i/o devices.
bool stop();
// Where all the action really happens // Where all the action really happens
int work(int noutput_items, int work(int noutput_items,
gr_vector_const_void_star &input_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
// Called by gnuradio to enable drivers, etc for i/o devices. private:
bool start(); boost::mutex d_mutex;
// Called by gnuradio to disable drivers, etc for i/o devices. pcap_t *descr; //ethernet pcap device descriptor
bool stop(); char *fifo_buff;
int fifo_read_ptr;
int fifo_write_ptr;
int fifo_items;
int d_sock_raw;
int d_udp_port;
struct sockaddr_in si_me;
std::string d_src_device;
std::string d_origin_address;
int d_udp_payload_size;
bool d_fifo_full;
int d_n_baseband_channels;
int d_wire_sample_type;
int d_bytes_per_sample;
size_t d_item_size;
bool d_IQ_swap;
boost::thread *d_pcap_thread;
void demux_samples(gr_vector_void_star output_items, int num_samples_readed);
void my_pcap_loop_thread(pcap_t *pcap_handle);
void pcap_callback(u_char *args, const struct pcap_pkthdr *pkthdr, const u_char *packet);
static void static_pcap_callback(u_char *args, const struct pcap_pkthdr *pkthdr, const u_char *packet);
/*
* Opens the ethernet device using libpcap raw capture mode
* If any of these fail, the fuction retuns the error and exits.
*/
bool open();
}; };
#endif /* GNSS_SDR_GR_COMPLEX_IP_PACKET_SOURCE_H */ #endif /* GNSS_SDR_GR_COMPLEX_IP_PACKET_SOURCE_H */

View File

@ -42,16 +42,34 @@ class labsat23_source;
using labsat23_source_sptr = boost::shared_ptr<labsat23_source>; using labsat23_source_sptr = boost::shared_ptr<labsat23_source>;
labsat23_source_sptr labsat23_make_source_sptr(const char *signal_file_basename, int channel_selector, gr::msg_queue::sptr queue); labsat23_source_sptr labsat23_make_source_sptr(
const char *signal_file_basename,
int channel_selector,
gr::msg_queue::sptr queue);
/*! /*!
* \brief This class implements conversion between Labsat2 and 3 format byte packet samples to gr_complex * \brief This class implements conversion between Labsat2 and 3 format byte packet samples to gr_complex
*/ */
class labsat23_source : public gr::block class labsat23_source : public gr::block
{ {
public:
~labsat23_source();
int general_work(int noutput_items,
gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
private: private:
friend labsat23_source_sptr labsat23_make_source_sptr(const char *signal_file_basename, int channel_selector, gr::msg_queue::sptr queue); friend labsat23_source_sptr labsat23_make_source_sptr(
labsat23_source(const char *signal_file_basename, int channel_selector, gr::msg_queue::sptr queue); const char *signal_file_basename,
int channel_selector,
gr::msg_queue::sptr queue);
labsat23_source(const char *signal_file_basename,
int channel_selector,
gr::msg_queue::sptr queue);
std::string generate_filename(); std::string generate_filename();
void decode_samples_one_channel(int16_t input_short, gr_complex *out, int type); void decode_samples_one_channel(int16_t input_short, gr_complex *out, int type);
int getBit(uint8_t byte, int position); int getBit(uint8_t byte, int position);
@ -65,13 +83,6 @@ private:
uint8_t d_ref_clock; uint8_t d_ref_clock;
uint8_t d_bits_per_sample; uint8_t d_bits_per_sample;
gr::msg_queue::sptr d_queue; gr::msg_queue::sptr d_queue;
public:
~labsat23_source();
int general_work(int noutput_items,
gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
}; };
#endif #endif

View File

@ -75,7 +75,8 @@ class unpack_2bit_samples;
using unpack_2bit_samples_sptr = boost::shared_ptr<unpack_2bit_samples>; using unpack_2bit_samples_sptr = boost::shared_ptr<unpack_2bit_samples>;
unpack_2bit_samples_sptr make_unpack_2bit_samples(bool big_endian_bytes, unpack_2bit_samples_sptr make_unpack_2bit_samples(
bool big_endian_bytes,
size_t item_size, size_t item_size,
bool big_endian_items, bool big_endian_items,
bool reverse_interleaving = false); bool reverse_interleaving = false);
@ -87,12 +88,25 @@ unpack_2bit_samples_sptr make_unpack_2bit_samples(bool big_endian_bytes,
*/ */
class unpack_2bit_samples : public gr::sync_interpolator class unpack_2bit_samples : public gr::sync_interpolator
{ {
private: public:
friend unpack_2bit_samples_sptr ~unpack_2bit_samples();
make_unpack_2bit_samples_sptr(bool big_endian_bytes,
unpack_2bit_samples(bool big_endian_bytes,
size_t item_size, size_t item_size,
bool big_endian_items, bool big_endian_items,
bool reverse_interleaving); bool reverse_interleaving);
int work(int noutput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
private:
friend unpack_2bit_samples_sptr make_unpack_2bit_samples_sptr(
bool big_endian_bytes,
size_t item_size,
bool big_endian_items,
bool reverse_interleaving);
bool big_endian_bytes_; bool big_endian_bytes_;
size_t item_size_; size_t item_size_;
bool big_endian_items_; bool big_endian_items_;
@ -100,18 +114,6 @@ private:
bool swap_endian_bytes_; bool swap_endian_bytes_;
bool reverse_interleaving_; bool reverse_interleaving_;
std::vector<int8_t> work_buffer_; std::vector<int8_t> work_buffer_;
public:
unpack_2bit_samples(bool big_endian_bytes,
size_t item_size,
bool big_endian_items,
bool reverse_interleaving);
~unpack_2bit_samples();
int work(int noutput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
}; };
#endif #endif

View File

@ -49,15 +49,15 @@ unpack_byte_2bit_cpx_samples_sptr make_unpack_byte_2bit_cpx_samples();
*/ */
class unpack_byte_2bit_cpx_samples : public gr::sync_interpolator class unpack_byte_2bit_cpx_samples : public gr::sync_interpolator
{ {
private:
friend unpack_byte_2bit_cpx_samples_sptr make_unpack_byte_2bit_cpx_samples_sptr();
public: public:
unpack_byte_2bit_cpx_samples(); unpack_byte_2bit_cpx_samples();
~unpack_byte_2bit_cpx_samples(); ~unpack_byte_2bit_cpx_samples();
int work(int noutput_items, int work(int noutput_items,
gr_vector_const_void_star &input_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
private:
friend unpack_byte_2bit_cpx_samples_sptr make_unpack_byte_2bit_cpx_samples_sptr();
}; };
#endif #endif

View File

@ -45,16 +45,15 @@ unpack_byte_2bit_samples_sptr make_unpack_byte_2bit_samples();
*/ */
class unpack_byte_2bit_samples : public gr::sync_interpolator class unpack_byte_2bit_samples : public gr::sync_interpolator
{ {
private:
friend unpack_byte_2bit_samples_sptr
make_unpack_byte_2bit_samples_sptr();
public: public:
unpack_byte_2bit_samples(); unpack_byte_2bit_samples();
~unpack_byte_2bit_samples(); ~unpack_byte_2bit_samples();
int work(int noutput_items, int work(int noutput_items,
gr_vector_const_void_star &input_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
private:
friend unpack_byte_2bit_samples_sptr make_unpack_byte_2bit_samples_sptr();
}; };
#endif #endif

View File

@ -47,15 +47,15 @@ unpack_byte_4bit_samples_sptr make_unpack_byte_4bit_samples();
*/ */
class unpack_byte_4bit_samples : public gr::sync_interpolator class unpack_byte_4bit_samples : public gr::sync_interpolator
{ {
private:
friend unpack_byte_4bit_samples_sptr make_unpack_byte_4bit_samples_sptr();
public: public:
unpack_byte_4bit_samples(); unpack_byte_4bit_samples();
~unpack_byte_4bit_samples(); ~unpack_byte_4bit_samples();
int work(int noutput_items, int work(int noutput_items,
gr_vector_const_void_star &input_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
private:
friend unpack_byte_4bit_samples_sptr make_unpack_byte_4bit_samples_sptr();
}; };
#endif #endif

View File

@ -45,16 +45,15 @@ unpack_intspir_1bit_samples_sptr make_unpack_intspir_1bit_samples();
*/ */
class unpack_intspir_1bit_samples : public gr::sync_interpolator class unpack_intspir_1bit_samples : public gr::sync_interpolator
{ {
private:
friend unpack_intspir_1bit_samples_sptr
make_unpack_intspir_1bit_samples_sptr();
public: public:
unpack_intspir_1bit_samples(); unpack_intspir_1bit_samples();
~unpack_intspir_1bit_samples(); ~unpack_intspir_1bit_samples();
int work(int noutput_items, int work(int noutput_items,
gr_vector_const_void_star &input_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
private:
friend unpack_intspir_1bit_samples_sptr make_unpack_intspir_1bit_samples_sptr();
}; };
#endif #endif

View File

@ -41,11 +41,13 @@
#include <cstddef> // for size_t #include <cstddef> // for size_t
#include <cstdint> #include <cstdint>
boost::shared_ptr<gr::block> gnss_sdr_make_valve(size_t sizeof_stream_item, boost::shared_ptr<gr::block> gnss_sdr_make_valve(
size_t sizeof_stream_item,
uint64_t nitems, uint64_t nitems,
gr::msg_queue::sptr queue); gr::msg_queue::sptr queue);
boost::shared_ptr<gr::block> gnss_sdr_make_valve(size_t sizeof_stream_item, boost::shared_ptr<gr::block> gnss_sdr_make_valve(
size_t sizeof_stream_item,
uint64_t nitems, uint64_t nitems,
gr::msg_queue::sptr queue, gr::msg_queue::sptr queue,
bool stop_flowgraph); bool stop_flowgraph);
@ -56,29 +58,34 @@ boost::shared_ptr<gr::block> gnss_sdr_make_valve(size_t sizeof_stream_item,
*/ */
class Gnss_Sdr_Valve : public gr::sync_block class Gnss_Sdr_Valve : public gr::sync_block
{ {
friend boost::shared_ptr<gr::block> gnss_sdr_make_valve(size_t sizeof_stream_item, public:
void open_valve();
int work(int noutput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
private:
friend boost::shared_ptr<gr::block> gnss_sdr_make_valve(
size_t sizeof_stream_item,
uint64_t nitems, uint64_t nitems,
gr::msg_queue::sptr queue); gr::msg_queue::sptr queue);
friend boost::shared_ptr<gr::block> gnss_sdr_make_valve(size_t sizeof_stream_item,
friend boost::shared_ptr<gr::block> gnss_sdr_make_valve(
size_t sizeof_stream_item,
uint64_t nitems, uint64_t nitems,
gr::msg_queue::sptr queue, gr::msg_queue::sptr queue,
bool stop_flowgraph); bool stop_flowgraph);
Gnss_Sdr_Valve(size_t sizeof_stream_item,
uint64_t nitems,
gr::msg_queue::sptr queue, bool stop_flowgraph);
uint64_t d_nitems; uint64_t d_nitems;
uint64_t d_ncopied_items; uint64_t d_ncopied_items;
gr::msg_queue::sptr d_queue; gr::msg_queue::sptr d_queue;
bool d_stop_flowgraph; bool d_stop_flowgraph;
bool d_open_valve; bool d_open_valve;
public:
Gnss_Sdr_Valve(size_t sizeof_stream_item,
uint64_t nitems,
gr::msg_queue::sptr queue, bool stop_flowgraph);
void open_valve();
int work(int noutput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
}; };
#endif /*GNSS_SDR_GNSS_SDR_VALVE_H_*/ #endif /*GNSS_SDR_GNSS_SDR_VALVE_H_*/

View File

@ -41,11 +41,6 @@
*/ */
class Rtl_Tcp_Dongle_Info class Rtl_Tcp_Dongle_Info
{ {
private:
char magic_[4]{};
uint32_t tuner_type_;
uint32_t tuner_gain_count_;
public: public:
enum enum
{ {
@ -77,6 +72,11 @@ public:
{ {
return tuner_gain_count_; return tuner_gain_count_;
} }
private:
char magic_[4]{};
uint32_t tuner_type_;
uint32_t tuner_gain_count_;
}; };

View File

@ -47,6 +47,15 @@
*/ */
class Tracking_2nd_DLL_filter class Tracking_2nd_DLL_filter
{ {
public:
void set_DLL_BW(float dll_bw_hz); //!< Set DLL filter bandwidth [Hz]
void set_pdi(float pdi_code); //!< Set Summation interval for code [s]
void initialize(); //!< Start tracking with acquisition information
float get_code_nco(float DLL_discriminator); //!< Numerically controlled oscillator
Tracking_2nd_DLL_filter(float pdi_code);
Tracking_2nd_DLL_filter();
~Tracking_2nd_DLL_filter();
private: private:
// PLL filter parameters // PLL filter parameters
float d_tau1_code = 0.0; float d_tau1_code = 0.0;
@ -57,15 +66,6 @@ private:
float d_old_code_error = 0.0; float d_old_code_error = 0.0;
float d_old_code_nco = 0.0; float d_old_code_nco = 0.0;
void calculate_lopp_coef(float* tau1, float* tau2, float lbw, float zeta, float k); void calculate_lopp_coef(float* tau1, float* tau2, float lbw, float zeta, float k);
public:
void set_DLL_BW(float dll_bw_hz); //! Set DLL filter bandwidth [Hz]
void set_pdi(float pdi_code); //! Set Summation interval for code [s]
void initialize(); //! Start tracking with acquisition information
float get_code_nco(float DLL_discriminator); //! Numerically controlled oscillator
Tracking_2nd_DLL_filter(float pdi_code);
Tracking_2nd_DLL_filter();
~Tracking_2nd_DLL_filter();
}; };
#endif #endif

View File

@ -46,28 +46,25 @@
*/ */
class Tracking_2nd_PLL_filter class Tracking_2nd_PLL_filter
{ {
private:
// PLL filter parameters
float d_tau1_carr = 0.0;
float d_tau2_carr = 0.0;
float d_pdi_carr = 0.0;
float d_pllnoisebandwidth = 0.0;
float d_plldampingratio = 0.0;
float d_old_carr_error = 0.0;
float d_old_carr_nco = 0.0;
void calculate_lopp_coef(float* tau1, float* tau2, float lbw, float zeta, float k);
public: public:
void set_PLL_BW(float pll_bw_hz); //! Set PLL loop bandwidth [Hz] void set_PLL_BW(float pll_bw_hz); //!< Set PLL loop bandwidth [Hz]
void set_pdi(float pdi_carr); //! Set Summation interval for code [s] void set_pdi(float pdi_carr); //!< Set Summation interval for code [s]
void initialize(); void initialize();
float get_carrier_nco(float PLL_discriminator); float get_carrier_nco(float PLL_discriminator);
Tracking_2nd_PLL_filter(float pdi_carr); Tracking_2nd_PLL_filter(float pdi_carr);
Tracking_2nd_PLL_filter(); Tracking_2nd_PLL_filter();
~Tracking_2nd_PLL_filter(); ~Tracking_2nd_PLL_filter();
private:
// PLL filter parameters
float d_tau1_carr = 0.0;
float d_tau2_carr = 0.0;
float d_pdi_carr = 0.0;
float d_pllnoisebandwidth = 0.0;
float d_plldampingratio = 0.0;
float d_old_carr_error = 0.0;
float d_old_carr_nco = 0.0;
void calculate_lopp_coef(float* tau1, float* tau2, float lbw, float zeta, float k);
}; };
#endif #endif

View File

@ -36,6 +36,13 @@
*/ */
class Tracking_FLL_PLL_filter class Tracking_FLL_PLL_filter
{ {
public:
void set_params(float fll_bw_hz, float pll_bw_hz, int order);
void initialize(float d_acq_carrier_doppler_hz);
float get_carrier_error(float FLL_discriminator, float PLL_discriminator, float correlation_time_s);
Tracking_FLL_PLL_filter();
~Tracking_FLL_PLL_filter();
private: private:
// FLL + PLL filter parameters // FLL + PLL filter parameters
int d_order; int d_order;
@ -49,13 +56,6 @@ private:
float d_pll_w0p2; float d_pll_w0p2;
float d_pll_b3; float d_pll_b3;
float d_pll_w0p; float d_pll_w0p;
public:
void set_params(float fll_bw_hz, float pll_bw_hz, int order);
void initialize(float d_acq_carrier_doppler_hz);
float get_carrier_error(float FLL_discriminator, float PLL_discriminator, float correlation_time_s);
Tracking_FLL_PLL_filter();
~Tracking_FLL_PLL_filter();
}; };
#endif #endif

View File

@ -43,6 +43,27 @@
*/ */
class Tracking_loop_filter class Tracking_loop_filter
{ {
public:
float get_noise_bandwidth(void) const;
float get_update_interval(void) const;
bool get_include_last_integrator(void) const;
int get_order(void) const;
void set_noise_bandwidth(float noise_bandwidth);
void set_update_interval(float update_interval);
void set_include_last_integrator(bool include_last_integrator);
void set_order(int loop_order);
void initialize(float initial_output = 0.0);
float apply(float current_input);
Tracking_loop_filter(float update_interval, float noise_bandwidth,
int loop_order = 2,
bool include_last_integrator = false);
Tracking_loop_filter();
~Tracking_loop_filter();
private: private:
// Store the last inputs and outputs: // Store the last inputs and outputs:
std::vector<float> d_inputs; std::vector<float> d_inputs;
@ -71,27 +92,6 @@ private:
// Compute the filter coefficients: // Compute the filter coefficients:
void update_coefficients(void); void update_coefficients(void);
public:
float get_noise_bandwidth(void) const;
float get_update_interval(void) const;
bool get_include_last_integrator(void) const;
int get_order(void) const;
void set_noise_bandwidth(float noise_bandwidth);
void set_update_interval(float update_interval);
void set_include_last_integrator(bool include_last_integrator);
void set_order(int loop_order);
void initialize(float initial_output = 0.0);
float apply(float current_input);
Tracking_loop_filter(float update_interval, float noise_bandwidth,
int loop_order = 2,
bool include_last_integrator = false);
Tracking_loop_filter();
~Tracking_loop_filter();
}; };
#endif #endif

View File

@ -47,6 +47,13 @@ gnss_sdr_fpga_sample_counter_sptr gnss_sdr_make_fpga_sample_counter(double _fs,
class gnss_sdr_fpga_sample_counter : public gr::block class gnss_sdr_fpga_sample_counter : public gr::block
{ {
public:
~gnss_sdr_fpga_sample_counter();
int general_work(int noutput_items,
gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
private: private:
friend gnss_sdr_fpga_sample_counter_sptr gnss_sdr_make_fpga_sample_counter(double _fs, int32_t _interval_ms); friend gnss_sdr_fpga_sample_counter_sptr gnss_sdr_make_fpga_sample_counter(double _fs, int32_t _interval_ms);
gnss_sdr_fpga_sample_counter(double _fs, int32_t _interval_ms); gnss_sdr_fpga_sample_counter(double _fs, int32_t _interval_ms);
@ -80,13 +87,6 @@ private:
volatile uint32_t *map_base; // driver memory map volatile uint32_t *map_base; // driver memory map
std::string device_name = "/dev/uio2"; // HW device name std::string device_name = "/dev/uio2"; // HW device name
bool is_open; bool is_open;
public:
~gnss_sdr_fpga_sample_counter();
int general_work(int noutput_items,
gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
}; };
#endif // GNSS_SDR_GNSS_SDR_FPGA_SAMPLE_COUNTER_H_ #endif // GNSS_SDR_GNSS_SDR_FPGA_SAMPLE_COUNTER_H_

View File

@ -50,9 +50,22 @@ gnss_sdr_sample_counter_sptr gnss_sdr_make_sample_counter(
class gnss_sdr_sample_counter : public gr::sync_decimator class gnss_sdr_sample_counter : public gr::sync_decimator
{ {
public:
~gnss_sdr_sample_counter();
int work(int noutput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
private: private:
friend gnss_sdr_sample_counter_sptr gnss_sdr_make_sample_counter(double _fs, int32_t _interval_ms, size_t _size); friend gnss_sdr_sample_counter_sptr gnss_sdr_make_sample_counter(
gnss_sdr_sample_counter(double _fs, int32_t _interval_ms, size_t _size); double _fs,
int32_t _interval_ms,
size_t _size);
gnss_sdr_sample_counter(double _fs,
int32_t _interval_ms,
size_t _size);
uint32_t samples_per_output; uint32_t samples_per_output;
double fs; double fs;
uint64_t sample_counter; uint64_t sample_counter;
@ -67,12 +80,6 @@ private:
uint32_t current_days; // Receiver time in days since the beginning of the run uint32_t current_days; // Receiver time in days since the beginning of the run
int32_t report_interval_ms; int32_t report_interval_ms;
bool flag_enable_send_msg; bool flag_enable_send_msg;
public:
~gnss_sdr_sample_counter();
int work(int noutput_items,
gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
}; };
#endif /*GNSS_SDR_GNSS_SDR_SAMPLE_COUNTER_H_*/ #endif /*GNSS_SDR_GNSS_SDR_SAMPLE_COUNTER_H_*/

View File

@ -62,19 +62,10 @@ extern "C"
*/ */
class Gnss_Sdr_Supl_Client class Gnss_Sdr_Supl_Client
{ {
private:
// GSM CELL INFO
int mcc;
int mns;
int lac;
int ci;
// assistance protocol structure
supl_ctx_t ctx{};
// assistance data
supl_assist_t assist{};
bool read_gal_almanac_from_gsa(const std::string& file_name);
public: public:
Gnss_Sdr_Supl_Client();
~Gnss_Sdr_Supl_Client();
// SUPL SERVER INFO // SUPL SERVER INFO
std::string server_name; std::string server_name;
int server_port; int server_port;
@ -113,6 +104,7 @@ public:
* \return Error code -> 0 no errors. * \return Error code -> 0 no errors.
*/ */
int get_assistance(int i_mcc, int i_mns, int i_lac, int i_ci); int get_assistance(int i_mcc, int i_mns, int i_lac, int i_ci);
/* /*
* \brief Read the received SUPL data and stores it into the corresponding class members (gps_ephemeris_map, gps_almanac_map, gps_iono, gps_time, gps_utc, gps_acq_map, and gps_ref_loc) * \brief Read the received SUPL data and stores it into the corresponding class members (gps_ephemeris_map, gps_almanac_map, gps_iono, gps_time, gps_utc, gps_acq_map, and gps_ref_loc)
* *
@ -270,8 +262,17 @@ public:
*/ */
void print_assistance(); void print_assistance();
Gnss_Sdr_Supl_Client(); private:
~Gnss_Sdr_Supl_Client(); // GSM CELL INFO
int mcc;
int mns;
int lac;
int ci;
// assistance protocol structure
supl_ctx_t ctx{};
// assistance data
supl_assist_t assist{};
bool read_gal_almanac_from_gsa(const std::string& file_name);
}; };
#endif #endif

View File

@ -45,6 +45,13 @@ gnss_sdr_time_counter_sptr gnss_sdr_make_time_counter();
class gnss_sdr_time_counter : public gr::block class gnss_sdr_time_counter : public gr::block
{ {
public:
~gnss_sdr_time_counter();
int general_work(int noutput_items __attribute__((unused)),
gr_vector_int &ninput_items __attribute__((unused)),
gr_vector_const_void_star &input_items __attribute__((unused)),
gr_vector_void_star &output_items);
private: private:
gnss_sdr_time_counter(); gnss_sdr_time_counter();
int64_t current_T_rx_ms; // Receiver time in ms since the beginning of the run int64_t current_T_rx_ms; // Receiver time in ms since the beginning of the run
@ -57,11 +64,6 @@ private:
uint32_t current_days; // Receiver time in days since the beginning of the run uint32_t current_days; // Receiver time in days since the beginning of the run
int32_t report_interval_ms; int32_t report_interval_ms;
friend gnss_sdr_time_counter_sptr gnss_sdr_make_time_counter(); friend gnss_sdr_time_counter_sptr gnss_sdr_make_time_counter();
public:
~gnss_sdr_time_counter();
int general_work(int noutput_items __attribute__((unused)), gr_vector_int &ninput_items __attribute__((unused)),
gr_vector_const_void_star &input_items __attribute__((unused)), gr_vector_void_star &output_items);
}; };
#endif /*GNSS_SDR_GNSS_SDR_SAMPLE_COUNTER_H_*/ #endif /*GNSS_SDR_GNSS_SDR_SAMPLE_COUNTER_H_*/

View File

@ -60,6 +60,12 @@ gnss_synchro_monitor_sptr gnss_synchro_make_monitor(unsigned int n_channels,
*/ */
class gnss_synchro_monitor : public gr::sync_block class gnss_synchro_monitor : public gr::sync_block
{ {
public:
~gnss_synchro_monitor(); //!< Default destructor
int work(int noutput_items, gr_vector_const_void_star& input_items,
gr_vector_void_star& output_items);
private: private:
friend gnss_synchro_monitor_sptr gnss_synchro_make_monitor(unsigned int n_channels, friend gnss_synchro_monitor_sptr gnss_synchro_make_monitor(unsigned int n_channels,
int decimation_factor, int decimation_factor,
@ -77,12 +83,6 @@ private:
int d_decimation_factor; int d_decimation_factor;
std::unique_ptr<Gnss_Synchro_Udp_Sink> udp_sink_ptr; std::unique_ptr<Gnss_Synchro_Udp_Sink> udp_sink_ptr;
int count; int count;
public:
~gnss_synchro_monitor(); //!< Default destructor
int work(int noutput_items, gr_vector_const_void_star& input_items,
gr_vector_void_star& output_items);
}; };
#endif #endif

View File

@ -46,10 +46,6 @@ template <typename Data>
class Concurrent_Map class Concurrent_Map
{ {
typedef typename std::map<int, Data>::iterator Data_iterator; // iterator is scope dependent typedef typename std::map<int, Data>::iterator Data_iterator; // iterator is scope dependent
private:
std::map<int, Data> the_map;
boost::mutex the_mutex;
public: public:
void write(int key, Data const& data) void write(int key, Data const& data)
{ {
@ -97,6 +93,10 @@ public:
lock.unlock(); lock.unlock();
return false; return false;
} }
private:
std::map<int, Data> the_map;
boost::mutex the_mutex;
}; };
#endif #endif

View File

@ -45,11 +45,6 @@ template <typename Data>
*/ */
class Concurrent_Queue class Concurrent_Queue
{ {
private:
std::queue<Data> the_queue;
mutable boost::mutex the_mutex;
boost::condition_variable the_condition_variable;
public: public:
void push(Data const& data) void push(Data const& data)
{ {
@ -87,5 +82,10 @@ public:
popped_value = the_queue.front(); popped_value = the_queue.front();
the_queue.pop(); the_queue.pop();
} }
private:
std::queue<Data> the_queue;
mutable boost::mutex the_mutex;
boost::condition_variable the_condition_variable;
}; };
#endif #endif

View File

@ -44,18 +44,13 @@
*/ */
class Beidou_Dnav_Ephemeris class Beidou_Dnav_Ephemeris
{ {
private:
/*
* Accounts for the beginning or end of week crossover
*
* See paragraph 20.3.3.3.3.1 (IS-GPS-200E)
* \param[in] - time in seconds
* \param[out] - corrected time, in seconds
*/
double check_t(double time);
public: public:
unsigned int i_satellite_PRN; // SV PRN NUMBER /*!
* Default constructor
*/
Beidou_Dnav_Ephemeris();
unsigned int i_satellite_PRN; //!< SV PRN NUMBER
double d_TOW; //!< Time of BEIDOU Week of the ephemeris set (taken from subframes TOW) [s] double d_TOW; //!< Time of BEIDOU Week of the ephemeris set (taken from subframes TOW) [s]
double d_Crs; //!< Amplitude of the Sine Harmonic Correction Term to the Orbit Radius [m] double d_Crs; //!< Amplitude of the Sine Harmonic Correction Term to the Orbit Radius [m]
double d_Delta_n; //!< Mean Motion Difference From Computed Value [semi-circles/s] double d_Delta_n; //!< Mean Motion Difference From Computed Value [semi-circles/s]
@ -124,6 +119,25 @@ public:
std::map<int, std::string> satelliteBlock; //!< Map that stores to which block the PRN belongs http://www.navcen.uscg.gov/?Do=constellationStatus std::map<int, std::string> satelliteBlock; //!< Map that stores to which block the PRN belongs http://www.navcen.uscg.gov/?Do=constellationStatus
/*!
* \brief Compute the ECEF SV coordinates and ECEF velocity
* Implementation of Table 20-IV (IS-GPS-200E)
* and compute the clock bias term including relativistic effect (return value)
*/
double satellitePosition(double transmitTime);
/*!
* \brief Sets (\a d_satClkDrift)and returns the clock drift in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_drift(double transmitTime);
/*!
* \brief Sets (\a d_dtr) and returns the clock relativistic correction term in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_relativistic_term(double transmitTime);
template <class Archive> template <class Archive>
/*! /*!
@ -177,30 +191,15 @@ public:
archive& make_nvp("b_antispoofing_flag", b_antispoofing_flag); //!< If true, the AntiSpoofing mode is ON in that SV archive& make_nvp("b_antispoofing_flag", b_antispoofing_flag); //!< If true, the AntiSpoofing mode is ON in that SV
} }
/*! private:
* \brief Compute the ECEF SV coordinates and ECEF velocity /*
* Implementation of Table 20-IV (IS-GPS-200E) * Accounts for the beginning or end of week crossover
* and compute the clock bias term including relativistic effect (return value) *
* See paragraph 20.3.3.3.3.1 (IS-GPS-200E)
* \param[in] - time in seconds
* \param[out] - corrected time, in seconds
*/ */
double satellitePosition(double transmitTime); double check_t(double time);
/*!
* \brief Sets (\a d_satClkDrift)and returns the clock drift in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_drift(double transmitTime);
/*!
* \brief Sets (\a d_dtr) and returns the clock relativistic correction term in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_relativistic_term(double transmitTime);
/*!
* Default constructor
*/
Beidou_Dnav_Ephemeris();
}; };
#endif #endif

View File

@ -54,19 +54,6 @@
*/ */
class Beidou_Dnav_Navigation_Message class Beidou_Dnav_Navigation_Message
{ {
private:
uint64_t read_navigation_unsigned(std::bitset<BEIDOU_DNAV_SUBFRAME_DATA_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
int64_t read_navigation_signed(std::bitset<BEIDOU_DNAV_SUBFRAME_DATA_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
bool read_navigation_bool(std::bitset<BEIDOU_DNAV_SUBFRAME_DATA_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
void print_beidou_word_bytes(uint32_t BEIDOU_word);
/*
* Accounts for the beginning or end of week crossover
*
* \param[in] - time in seconds
* \param[out] - corrected time, in seconds
*/
double check_t(double time);
public: public:
/*! /*!
* Default constructor * Default constructor
@ -207,7 +194,7 @@ public:
// satellite identification info // satellite identification info
int32_t i_channel_ID; int32_t i_channel_ID;
int32_t i_signal_type; //!< BDS: data source (0:unknown,1:B1I,2:B1Q,3:B2I,4:B2Q,5:B3I,6:B3Q) int32_t i_signal_type; //!< BDS: data source (0:unknown,1:B1I,2:B1Q,3:B2I,4:B2Q,5:B3I,6:B3Q)
uint32_t i_satellite_PRN; uint32_t i_satellite_PRN;
// time synchro // time synchro
@ -321,6 +308,20 @@ public:
* \brief Returns true if new UTC model has arrived. The flag is set to false when the function is executed * \brief Returns true if new UTC model has arrived. The flag is set to false when the function is executed
*/ */
bool have_new_almanac(); bool have_new_almanac();
private:
uint64_t read_navigation_unsigned(std::bitset<BEIDOU_DNAV_SUBFRAME_DATA_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
int64_t read_navigation_signed(std::bitset<BEIDOU_DNAV_SUBFRAME_DATA_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
bool read_navigation_bool(std::bitset<BEIDOU_DNAV_SUBFRAME_DATA_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
void print_beidou_word_bytes(uint32_t BEIDOU_word);
/*
* Accounts for the beginning or end of week crossover
*
* \param[in] - time in seconds
* \param[out] - corrected time, in seconds
*/
double check_t(double time);
}; };
#endif #endif

View File

@ -52,14 +52,9 @@
*/ */
class Galileo_Navigation_Message class Galileo_Navigation_Message
{ {
private:
bool CRC_test(std::bitset<GALILEO_DATA_FRAME_BITS> bits, uint32_t checksum);
bool read_navigation_bool(std::bitset<GALILEO_DATA_JK_BITS> bits, const std::vector<std::pair<int32_t, int32_t> >& parameter);
uint64_t read_navigation_unsigned(std::bitset<GALILEO_DATA_JK_BITS> bits, const std::vector<std::pair<int32_t, int32_t> >& parameter);
uint64_t read_page_type_unsigned(std::bitset<GALILEO_PAGE_TYPE_BITS> bits, const std::vector<std::pair<int32_t, int32_t> >& parameter);
int64_t read_navigation_signed(std::bitset<GALILEO_DATA_JK_BITS> bits, const std::vector<std::pair<int32_t, int32_t> >& parameter);
public: public:
Galileo_Navigation_Message();
int32_t Page_type_time_stamp; int32_t Page_type_time_stamp;
int32_t flag_even_word; int32_t flag_even_word;
std::string page_Even; std::string page_Even;
@ -293,7 +288,12 @@ public:
*/ */
Galileo_Almanac_Helper get_almanac(); Galileo_Almanac_Helper get_almanac();
Galileo_Navigation_Message(); private:
bool CRC_test(std::bitset<GALILEO_DATA_FRAME_BITS> bits, uint32_t checksum);
bool read_navigation_bool(std::bitset<GALILEO_DATA_JK_BITS> bits, const std::vector<std::pair<int32_t, int32_t> >& parameter);
uint64_t read_navigation_unsigned(std::bitset<GALILEO_DATA_JK_BITS> bits, const std::vector<std::pair<int32_t, int32_t> >& parameter);
uint64_t read_page_type_unsigned(std::bitset<GALILEO_PAGE_TYPE_BITS> bits, const std::vector<std::pair<int32_t, int32_t> >& parameter);
int64_t read_navigation_signed(std::bitset<GALILEO_DATA_JK_BITS> bits, const std::vector<std::pair<int32_t, int32_t> >& parameter);
}; };
#endif /* GALILEO_NAVIGATION_MESSAGE_H_ */ #endif /* GALILEO_NAVIGATION_MESSAGE_H_ */

View File

@ -46,17 +46,12 @@
*/ */
class Glonass_Gnav_Ephemeris class Glonass_Gnav_Ephemeris
{ {
private:
/*
* Accounts for the beginning or end of week crossover
*
* See paragraph 20.3.3.3.3.1 (IS-GPS-200E)
* \param[in] - time in seconds
* \param[out] - corrected time, in seconds
*/
double check_t(double time);
public: public:
/*!
* Default constructor
*/
Glonass_Gnav_Ephemeris();
double d_m; //!< String number within frame [dimensionless] double d_m; //!< String number within frame [dimensionless]
double d_t_k; //!< GLONASS Time (UTC(SU) + 3 h) referenced to the beginning of the frame within the current day [s] double d_t_k; //!< GLONASS Time (UTC(SU) + 3 h) referenced to the beginning of the frame within the current day [s]
double d_t_b; //!< Reference ephemeris relative time in GLONASS Time (UTC(SU) + 3 h). Index of a time interval within current day according to UTC(SU) + 03 hours 00 min. [s] double d_t_b; //!< Reference ephemeris relative time in GLONASS Time (UTC(SU) + 3 h). Index of a time interval within current day according to UTC(SU) + 03 hours 00 min. [s]
@ -100,6 +95,38 @@ public:
double d_WN; //!< GLONASST IN GPST week number of the start of frame double d_WN; //!< GLONASST IN GPST week number of the start of frame
double d_tod; //!< Time of Day since ephemeris where decoded double d_tod; //!< Time of Day since ephemeris where decoded
/*!
* \brief Sets (\a d_satClkDrift)and returns the clock drift in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_drift(double transmitTime, double timeCorrUTC);
/*!
* \brief Computes the GLONASS System Time and returns a boost::posix_time::ptime object
* \ param offset_time Is the start of day offset to compute the time
*/
boost::posix_time::ptime compute_GLONASS_time(const double offset_time) const;
/*!
* \brief Converts from GLONASST to UTC
* \details The function simply adjust for the 6 hrs offset between GLONASST and UTC
* \param[in] offset_time Is the start of day offset
* \param[in] glot2utc_corr Correction from GLONASST to UTC
* \returns UTC time as a boost::posix_time::ptime object
*/
boost::posix_time::ptime glot_to_utc(const double offset_time, const double glot2utc_corr) const;
/*!
* \brief Converts from GLONASST to GPST
* \details Converts from GLONASST to GPST in time of week (TOW) and week number (WN) format
* \param[in] tod_offset Is the start of day offset
* \param[in] glot2utc_corr Correction from GLONASST to UTC
* \param[in] glot2gpst_corr Correction from GLONASST to GPST
* \param[out] WN Week Number, not in mod(1024) format
* \param[out] TOW Time of Week in seconds of week
*/
void glot_to_gpst(double tod_offset, double glot2utc_corr, double glot2gpst_corr, double* WN, double* TOW) const;
template <class Archive> template <class Archive>
/*! /*!
@ -145,42 +172,15 @@ public:
archive& make_nvp("d_l5th_n", d_l5th_n); //!< Health flag for nth satellite; ln = 0 indicates the n-th satellite is helthy, ln = 1 indicates malfunction of this nth satellite [dimensionless] archive& make_nvp("d_l5th_n", d_l5th_n); //!< Health flag for nth satellite; ln = 0 indicates the n-th satellite is helthy, ln = 1 indicates malfunction of this nth satellite [dimensionless]
} }
/*! private:
* \brief Sets (\a d_satClkDrift)and returns the clock drift in seconds according to the User Algorithm for SV Clock Correction /*
* (IS-GPS-200E, 20.3.3.3.3.1) * Accounts for the beginning or end of week crossover
*
* See paragraph 20.3.3.3.3.1 (IS-GPS-200E)
* \param[in] - time in seconds
* \param[out] - corrected time, in seconds
*/ */
double sv_clock_drift(double transmitTime, double timeCorrUTC); double check_t(double time);
/*!
* \brief Computes the GLONASS System Time and returns a boost::posix_time::ptime object
* \ param offset_time Is the start of day offset to compute the time
*/
boost::posix_time::ptime compute_GLONASS_time(const double offset_time) const;
/*!
* \brief Converts from GLONASST to UTC
* \details The function simply adjust for the 6 hrs offset between GLONASST and UTC
* \param[in] offset_time Is the start of day offset
* \param[in] glot2utc_corr Correction from GLONASST to UTC
* \returns UTC time as a boost::posix_time::ptime object
*/
boost::posix_time::ptime glot_to_utc(const double offset_time, const double glot2utc_corr) const;
/*!
* \brief Converts from GLONASST to GPST
* \details Converts from GLONASST to GPST in time of week (TOW) and week number (WN) format
* \param[in] tod_offset Is the start of day offset
* \param[in] glot2utc_corr Correction from GLONASST to UTC
* \param[in] glot2gpst_corr Correction from GLONASST to GPST
* \param[out] WN Week Number, not in mod(1024) format
* \param[out] TOW Time of Week in seconds of week
*/
void glot_to_gpst(double tod_offset, double glot2utc_corr, double glot2gpst_corr, double* WN, double* TOW) const;
/*!
* Default constructor
*/
Glonass_Gnav_Ephemeris();
}; };
#endif #endif

View File

@ -41,9 +41,9 @@
#include "glonass_gnav_utc_model.h" #include "glonass_gnav_utc_model.h"
#include <bitset> #include <bitset>
#include <cstdint> #include <cstdint>
#include <utility> // for pair
#include <vector> // for vector
#include <string> #include <string>
#include <utility> // for pair
#include <vector> // for vector
/*! /*!
@ -53,12 +53,12 @@
*/ */
class Glonass_Gnav_Navigation_Message class Glonass_Gnav_Navigation_Message
{ {
private:
uint64_t read_navigation_unsigned(std::bitset<GLONASS_GNAV_STRING_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
int64_t read_navigation_signed(std::bitset<GLONASS_GNAV_STRING_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
bool read_navigation_bool(std::bitset<GLONASS_GNAV_STRING_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
public: public:
/*!
* Default constructor
*/
Glonass_Gnav_Navigation_Message();
bool flag_CRC_test; bool flag_CRC_test;
uint32_t d_frame_ID; uint32_t d_frame_ID;
uint32_t d_string_ID; uint32_t d_string_ID;
@ -164,10 +164,10 @@ public:
*/ */
int32_t string_decoder(const std::string& frame_string); int32_t string_decoder(const std::string& frame_string);
/*! private:
* Default constructor uint64_t read_navigation_unsigned(std::bitset<GLONASS_GNAV_STRING_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
*/ int64_t read_navigation_signed(std::bitset<GLONASS_GNAV_STRING_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
Glonass_Gnav_Navigation_Message(); bool read_navigation_bool(std::bitset<GLONASS_GNAV_STRING_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
}; };
#endif #endif

View File

@ -45,6 +45,11 @@
class Glonass_Gnav_Utc_Model class Glonass_Gnav_Utc_Model
{ {
public: public:
/*!
* Default constructor
*/
Glonass_Gnav_Utc_Model();
bool valid; bool valid;
// Clock Parameters // Clock Parameters
double d_tau_c; //!< GLONASS time scale correction to UTC(SU) time. [s] double d_tau_c; //!< GLONASS time scale correction to UTC(SU) time. [s]
@ -54,6 +59,12 @@ public:
double d_B1; //!< Coefficient to determine DeltaUT1 [s] double d_B1; //!< Coefficient to determine DeltaUT1 [s]
double d_B2; //!< Coefficient to determine DeltaUT1 [s/msd] double d_B2; //!< Coefficient to determine DeltaUT1 [s/msd]
/*!
* \brief Computes the Coordinated Universal Time (UTC) and
* returns it in [s] (GLONASS ICD (Edition 5.1) Section 3.3.3 GLONASS Time)
*/
double utc_time(double glonass_time_corrected);
template <class Archive> template <class Archive>
/*! /*!
* \brief Serialize is a boost standard method to be called by the boost XML serialization. Here is used to save the almanac data on disk file. * \brief Serialize is a boost standard method to be called by the boost XML serialization. Here is used to save the almanac data on disk file.
@ -72,17 +83,6 @@ public:
archive& make_nvp("d_B1", d_B1); archive& make_nvp("d_B1", d_B1);
archive& make_nvp("d_B2", d_B2); archive& make_nvp("d_B2", d_B2);
} }
/*!
* Default constructor
*/
Glonass_Gnav_Utc_Model();
/*!
* \brief Computes the Coordinated Universal Time (UTC) and
* returns it in [s] (GLONASS ICD (Edition 5.1) Section 3.3.3 GLONASS Time)
*/
double utc_time(double glonass_time_corrected);
}; };
#endif #endif

View File

@ -43,10 +43,6 @@
*/ */
class Gnss_Signal class Gnss_Signal
{ {
private:
Gnss_Satellite satellite;
std::string signal;
public: public:
Gnss_Signal(); Gnss_Signal();
Gnss_Signal(const std::string& signal_); Gnss_Signal(const std::string& signal_);
@ -57,6 +53,10 @@ public:
friend bool operator==(const Gnss_Signal& /*sig1*/, const Gnss_Signal& /*sig2*/); //!< operator== for comparison friend bool operator==(const Gnss_Signal& /*sig1*/, const Gnss_Signal& /*sig2*/); //!< operator== for comparison
friend std::ostream& operator<<(std::ostream& /*out*/, const Gnss_Signal& /*sig*/); //!< operator<< for pretty printing friend std::ostream& operator<<(std::ostream& /*out*/, const Gnss_Signal& /*sig*/); //!< operator<< for pretty printing
private:
Gnss_Satellite satellite;
std::string signal;
}; };
#endif #endif

View File

@ -43,10 +43,12 @@
*/ */
class Gps_CNAV_Ephemeris class Gps_CNAV_Ephemeris
{ {
private:
double check_t(double time);
public: public:
/*!
* Default constructor
*/
Gps_CNAV_Ephemeris();
uint32_t i_satellite_PRN; // SV PRN NUMBER uint32_t i_satellite_PRN; // SV PRN NUMBER
// Message Types 10 and 11 Parameters (1 of 2) // Message Types 10 and 11 Parameters (1 of 2)
@ -122,6 +124,24 @@ public:
double d_satvel_Y; //!< Earth-fixed velocity coordinate y of the satellite [m] double d_satvel_Y; //!< Earth-fixed velocity coordinate y of the satellite [m]
double d_satvel_Z; //!< Earth-fixed velocity coordinate z of the satellite [m] double d_satvel_Z; //!< Earth-fixed velocity coordinate z of the satellite [m]
/*!
* \brief Compute the ECEF SV coordinates and ECEF velocity
* Implementation of Table 20-IV (IS-GPS-200E)
*/
double satellitePosition(double transmitTime);
/*!
* \brief Sets (\a d_satClkDrift)and returns the clock drift in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_drift(double transmitTime);
/*!
* \brief Sets (\a d_dtr) and returns the clock relativistic correction term in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_relativistic_term(double transmitTime);
template <class Archive> template <class Archive>
/*! /*!
@ -170,27 +190,8 @@ public:
archive& make_nvp("b_antispoofing_flag", b_antispoofing_flag); //!< If true, the AntiSpoofing mode is ON in that SV archive& make_nvp("b_antispoofing_flag", b_antispoofing_flag); //!< If true, the AntiSpoofing mode is ON in that SV
} }
/*! private:
* \brief Compute the ECEF SV coordinates and ECEF velocity double check_t(double time);
* Implementation of Table 20-IV (IS-GPS-200E)
*/
double satellitePosition(double transmitTime);
/*!
* \brief Sets (\a d_satClkDrift)and returns the clock drift in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_drift(double transmitTime);
/*!
* \brief Sets (\a d_dtr) and returns the clock relativistic correction term in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_relativistic_term(double transmitTime);
/*!
* Default constructor
*/
Gps_CNAV_Ephemeris();
}; };
#endif #endif

View File

@ -55,16 +55,12 @@
*/ */
class Gps_CNAV_Navigation_Message class Gps_CNAV_Navigation_Message
{ {
private:
uint64_t read_navigation_unsigned(std::bitset<GPS_CNAV_DATA_PAGE_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
int64_t read_navigation_signed(std::bitset<GPS_CNAV_DATA_PAGE_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
bool read_navigation_bool(std::bitset<GPS_CNAV_DATA_PAGE_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
Gps_CNAV_Ephemeris ephemeris_record;
Gps_CNAV_Iono iono_record;
Gps_CNAV_Utc_Model utc_model_record;
public: public:
/*!
* Default constructor
*/
Gps_CNAV_Navigation_Message();
int32_t d_TOW; int32_t d_TOW;
bool b_flag_ephemeris_1; bool b_flag_ephemeris_1;
bool b_flag_ephemeris_2; bool b_flag_ephemeris_2;
@ -122,10 +118,14 @@ public:
*/ */
bool have_new_ephemeris(); bool have_new_ephemeris();
/*! private:
* Default constructor uint64_t read_navigation_unsigned(std::bitset<GPS_CNAV_DATA_PAGE_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
*/ int64_t read_navigation_signed(std::bitset<GPS_CNAV_DATA_PAGE_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
Gps_CNAV_Navigation_Message(); bool read_navigation_bool(std::bitset<GPS_CNAV_DATA_PAGE_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
Gps_CNAV_Ephemeris ephemeris_record;
Gps_CNAV_Iono iono_record;
Gps_CNAV_Utc_Model utc_model_record;
}; };
#endif #endif

View File

@ -46,17 +46,12 @@
*/ */
class Gps_Ephemeris class Gps_Ephemeris
{ {
private:
/*
* Accounts for the beginning or end of week crossover
*
* See paragraph 20.3.3.3.3.1 (IS-GPS-200E)
* \param[in] - time in seconds
* \param[out] - corrected time, in seconds
*/
double check_t(double time);
public: public:
/*!
* Default constructor
*/
Gps_Ephemeris();
uint32_t i_satellite_PRN; // SV PRN NUMBER uint32_t i_satellite_PRN; // SV PRN NUMBER
int32_t d_TOW; //!< Time of GPS Week of the ephemeris set (taken from subframes TOW) [s] int32_t d_TOW; //!< Time of GPS Week of the ephemeris set (taken from subframes TOW) [s]
double d_Crs; //!< Amplitude of the Sine Harmonic Correction Term to the Orbit Radius [m] double d_Crs; //!< Amplitude of the Sine Harmonic Correction Term to the Orbit Radius [m]
@ -127,6 +122,25 @@ public:
std::map<int, std::string> satelliteBlock; //!< Map that stores to which block the PRN belongs http://www.navcen.uscg.gov/?Do=constellationStatus std::map<int, std::string> satelliteBlock; //!< Map that stores to which block the PRN belongs http://www.navcen.uscg.gov/?Do=constellationStatus
/*!
* \brief Compute the ECEF SV coordinates and ECEF velocity
* Implementation of Table 20-IV (IS-GPS-200E)
* and compute the clock bias term including relativistic effect (return value)
*/
double satellitePosition(double transmitTime);
/*!
* \brief Sets (\a d_satClkDrift)and returns the clock drift in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_drift(double transmitTime);
/*!
* \brief Sets (\a d_dtr) and returns the clock relativistic correction term in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_relativistic_term(double transmitTime);
template <class Archive> template <class Archive>
/*! /*!
@ -182,29 +196,15 @@ public:
archive& make_nvp("b_antispoofing_flag", b_antispoofing_flag); //!< If true, the AntiSpoofing mode is ON in that SV archive& make_nvp("b_antispoofing_flag", b_antispoofing_flag); //!< If true, the AntiSpoofing mode is ON in that SV
} }
/*! private:
* \brief Compute the ECEF SV coordinates and ECEF velocity /*
* Implementation of Table 20-IV (IS-GPS-200E) * Accounts for the beginning or end of week crossover
* and compute the clock bias term including relativistic effect (return value) *
* See paragraph 20.3.3.3.3.1 (IS-GPS-200E)
* \param[in] - time in seconds
* \param[out] - corrected time, in seconds
*/ */
double satellitePosition(double transmitTime); double check_t(double time);
/*!
* \brief Sets (\a d_satClkDrift)and returns the clock drift in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_drift(double transmitTime);
/*!
* \brief Sets (\a d_dtr) and returns the clock relativistic correction term in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_relativistic_term(double transmitTime);
/*!
* Default constructor
*/
Gps_Ephemeris();
}; };
#endif #endif

View File

@ -52,13 +52,12 @@
*/ */
class Gps_Navigation_Message class Gps_Navigation_Message
{ {
private:
uint64_t read_navigation_unsigned(std::bitset<GPS_SUBFRAME_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
int64_t read_navigation_signed(std::bitset<GPS_SUBFRAME_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
bool read_navigation_bool(std::bitset<GPS_SUBFRAME_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
void print_gps_word_bytes(uint32_t GPS_word);
public: public:
/*!
* Default constructor
*/
Gps_Navigation_Message();
bool b_valid_ephemeris_set_flag; // flag indicating that this ephemeris set have passed the validation check bool b_valid_ephemeris_set_flag; // flag indicating that this ephemeris set have passed the validation check
// broadcast orbit 1 // broadcast orbit 1
int32_t d_TOW; //!< Time of GPS Week of the ephemeris set (taken from subframes TOW) [s] int32_t d_TOW; //!< Time of GPS Week of the ephemeris set (taken from subframes TOW) [s]
@ -208,10 +207,11 @@ public:
bool satellite_validation(); bool satellite_validation();
/*! private:
* Default constructor uint64_t read_navigation_unsigned(std::bitset<GPS_SUBFRAME_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
*/ int64_t read_navigation_signed(std::bitset<GPS_SUBFRAME_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
Gps_Navigation_Message(); bool read_navigation_bool(std::bitset<GPS_SUBFRAME_BITS> bits, const std::vector<std::pair<int32_t, int32_t>>& parameter);
void print_gps_word_bytes(uint32_t GPS_word);
}; };
#endif #endif

View File

@ -42,18 +42,16 @@ class Sbas_Ephemeris
{ {
public: public:
void print(std::ostream &out); void print(std::ostream &out);
int i_prn; //!< PRN number int i_prn; //!< PRN number
//gtime_t t0; // reference epoch time (GPST) int i_t0; //!< Reference epoch time (GPST)
int i_t0; double d_tof; //!< Time of message frame (GPST)
//gtime_t tof; // time of message frame (GPST) int i_sv_ura; //!< SV accuracy (URA index), not standardized
double d_tof; bool b_sv_do_not_use; //!< Health status (false:do not use / true:usable)
int i_sv_ura; //!< SV accuracy (URA index), not standardized double d_pos[3]; //!< Satellite position (m) (ECEF)
bool b_sv_do_not_use; //!< Health status (false:do not use / true:usable) double d_vel[3]; //!< Satellite velocity (m/s) (ECEF)
double d_pos[3]; //!< Satellite position (m) (ECEF) double d_acc[3]; //!< Satellite acceleration (m/s^2) (ECEF)
double d_vel[3]; //!< Satellite velocity (m/s) (ECEF) double d_af0; //!< Satellite clock-offset (s)
double d_acc[3]; //!< Satellite acceleration (m/s^2) (ECEF) double d_af1; //!< Satellite drift (s/s)
double d_af0; //!< Satellite clock-offset (s)
double d_af1; //!< Satellite drift (s/s)
}; };