1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2025-01-27 01:14:51 +00:00

Cleaning code and comments

git-svn-id: https://svn.code.sf.net/p/gnss-sdr/code/trunk@238 64b25241-fba3-4117-9849-534c7e92360d
This commit is contained in:
Carles Fernandez 2012-09-02 16:53:59 +00:00
parent cc02888dad
commit 10a4ac60df
3 changed files with 604 additions and 646 deletions

View File

@ -49,70 +49,70 @@ using google::LogMessage;
gps_l1_ca_pvt_cc_sptr gps_l1_ca_pvt_cc_sptr
gps_l1_ca_make_pvt_cc(unsigned int nchannels, gr_msg_queue_sptr queue, bool dump, std::string dump_filename, int averaging_depth, bool flag_averaging, int output_rate_ms, int display_rate_ms, bool flag_nmea_tty_port, std::string nmea_dump_filename, std::string nmea_dump_devname) gps_l1_ca_make_pvt_cc(unsigned int nchannels, gr_msg_queue_sptr queue, bool dump, std::string dump_filename, int averaging_depth, bool flag_averaging, int output_rate_ms, int display_rate_ms, bool flag_nmea_tty_port, std::string nmea_dump_filename, std::string nmea_dump_devname)
{ {
return gps_l1_ca_pvt_cc_sptr(new gps_l1_ca_pvt_cc(nchannels, queue, dump, dump_filename, averaging_depth, flag_averaging, output_rate_ms, display_rate_ms, flag_nmea_tty_port, nmea_dump_filename, nmea_dump_devname)); return gps_l1_ca_pvt_cc_sptr(new gps_l1_ca_pvt_cc(nchannels, queue, dump, dump_filename, averaging_depth, flag_averaging, output_rate_ms, display_rate_ms, flag_nmea_tty_port, nmea_dump_filename, nmea_dump_devname));
} }
gps_l1_ca_pvt_cc::gps_l1_ca_pvt_cc(unsigned int nchannels, gr_msg_queue_sptr queue, bool dump, std::string dump_filename, int averaging_depth, bool flag_averaging, int output_rate_ms, int display_rate_ms, bool flag_nmea_tty_port, std::string nmea_dump_filename, std::string nmea_dump_devname) : gps_l1_ca_pvt_cc::gps_l1_ca_pvt_cc(unsigned int nchannels, gr_msg_queue_sptr queue, bool dump, std::string dump_filename, int averaging_depth, bool flag_averaging, int output_rate_ms, int display_rate_ms, bool flag_nmea_tty_port, std::string nmea_dump_filename, std::string nmea_dump_devname) :
gr_block ("gps_l1_ca_pvt_cc", gr_make_io_signature (nchannels, nchannels, sizeof(Gnss_Synchro)), gr_block ("gps_l1_ca_pvt_cc", gr_make_io_signature (nchannels, nchannels, sizeof(Gnss_Synchro)),
gr_make_io_signature(1, 1, sizeof(gr_complex))) gr_make_io_signature(1, 1, sizeof(gr_complex)))
{ {
d_output_rate_ms = output_rate_ms; d_output_rate_ms = output_rate_ms;
d_display_rate_ms=display_rate_ms; d_display_rate_ms = display_rate_ms;
d_queue = queue; d_queue = queue;
d_dump = dump; d_dump = dump;
d_nchannels = nchannels; d_nchannels = nchannels;
d_dump_filename = dump_filename; d_dump_filename = dump_filename;
std::string dump_ls_pvt_filename; std::string dump_ls_pvt_filename = dump_filename;
dump_ls_pvt_filename=dump_filename;
//initialize kml_printer //initialize kml_printer
std::string kml_dump_filename; std::string kml_dump_filename;
kml_dump_filename = d_dump_filename; kml_dump_filename = d_dump_filename;
kml_dump_filename.append(".kml"); kml_dump_filename.append(".kml");
d_kml_dump.set_headers(kml_dump_filename); d_kml_dump.set_headers(kml_dump_filename);
//initialize nmea_printer //initialize nmea_printer
d_nmea_printer=new Nmea_Printer(nmea_dump_filename,flag_nmea_tty_port,nmea_dump_devname); d_nmea_printer = new Nmea_Printer(nmea_dump_filename, flag_nmea_tty_port, nmea_dump_devname);
d_dump_filename.append("_raw.dat"); d_dump_filename.append("_raw.dat");
dump_ls_pvt_filename.append("_ls_pvt.dat"); dump_ls_pvt_filename.append("_ls_pvt.dat");
d_averaging_depth = averaging_depth; d_averaging_depth = averaging_depth;
d_flag_averaging = flag_averaging; d_flag_averaging = flag_averaging;
d_ls_pvt = new gps_l1_ca_ls_pvt(nchannels,dump_ls_pvt_filename,d_dump); d_ls_pvt = new gps_l1_ca_ls_pvt(nchannels,dump_ls_pvt_filename,d_dump);
d_ls_pvt->set_averaging_depth(d_averaging_depth); d_ls_pvt->set_averaging_depth(d_averaging_depth);
d_ephemeris_clock_s = 0.0; d_ephemeris_clock_s = 0.0;
d_sample_counter = 0; d_sample_counter = 0;
d_tx_time=0.0; d_tx_time=0.0;
b_rinex_header_writen = false; b_rinex_header_writen = false;
rp = new Rinex_Printer(); rp = new Rinex_Printer();
for (unsigned int i=0; i<nchannels; i++) for (unsigned int i=0; i<nchannels; i++)
{ {
nav_data_map[i] = Gps_Navigation_Message(); nav_data_map[i] = Gps_Navigation_Message();
} }
// ############# ENABLE DATA FILE LOG ################# // ############# ENABLE DATA FILE LOG #################
if (d_dump == true) if (d_dump == true)
{ {
if (d_dump_file.is_open() == false) if (d_dump_file.is_open() == false)
{ {
try try
{ {
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit ); d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit );
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary); d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "PVT dump enabled Log file: " << d_dump_filename.c_str() << std::endl; std::cout << "PVT dump enabled Log file: " << d_dump_filename.c_str() << std::endl;
} }
catch (std::ifstream::failure e) { catch (std::ifstream::failure e)
std::cout << "Exception opening PVT dump file " << e.what() << std::endl; {
} std::cout << "Exception opening PVT dump file " << e.what() << std::endl;
} }
} }
}
} }
@ -120,94 +120,95 @@ gps_l1_ca_pvt_cc::gps_l1_ca_pvt_cc(unsigned int nchannels, gr_msg_queue_sptr que
gps_l1_ca_pvt_cc::~gps_l1_ca_pvt_cc() gps_l1_ca_pvt_cc::~gps_l1_ca_pvt_cc()
{ {
d_kml_dump.close_file(); d_kml_dump.close_file();
delete d_ls_pvt; delete d_ls_pvt;
delete rp; delete rp;
delete d_nmea_printer; delete d_nmea_printer;
} }
bool pseudoranges_pairCompare_min( std::pair<int,Gnss_Synchro> a, std::pair<int,Gnss_Synchro> b) bool pseudoranges_pairCompare_min( std::pair<int,Gnss_Synchro> a, std::pair<int,Gnss_Synchro> b)
{ {
return (a.second.Pseudorange_m) < (b.second.Pseudorange_m); return (a.second.Pseudorange_m) < (b.second.Pseudorange_m);
} }
int gps_l1_ca_pvt_cc::general_work (int noutput_items, gr_vector_int &ninput_items, int gps_l1_ca_pvt_cc::general_work (int noutput_items, gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items) gr_vector_const_void_star &input_items, gr_vector_void_star &output_items)
{ {
d_sample_counter++; d_sample_counter++;
std::map<int,Gnss_Synchro> gnss_pseudoranges_map; std::map<int,Gnss_Synchro> gnss_pseudoranges_map;
std::map<int,double> pseudoranges; std::map<int,double> pseudoranges;
std::map<int,Gnss_Synchro>::iterator gnss_pseudoranges_iter; std::map<int,Gnss_Synchro>::iterator gnss_pseudoranges_iter;
Gnss_Synchro **in = (Gnss_Synchro **) &input_items[0]; //Get the input pointer Gnss_Synchro **in = (Gnss_Synchro **) &input_items[0]; //Get the input pointer
for (unsigned int i=0; i<d_nchannels; i++) for (unsigned int i=0; i<d_nchannels; i++)
{ {
if (in[i][0].Flag_valid_pseudorange == true) if (in[i][0].Flag_valid_pseudorange == true)
{ {
gnss_pseudoranges_map.insert(std::pair<int,Gnss_Synchro>(in[i][0].PRN, in[i][0])); //record the valid pseudorange in a map gnss_pseudoranges_map.insert(std::pair<int,Gnss_Synchro>(in[i][0].PRN, in[i][0])); // store valid pseudoranges in a map
} }
} }
for(gnss_pseudoranges_iter = gnss_pseudoranges_map.begin(); for(gnss_pseudoranges_iter = gnss_pseudoranges_map.begin();
gnss_pseudoranges_iter != gnss_pseudoranges_map.end(); gnss_pseudoranges_iter != gnss_pseudoranges_map.end();
gnss_pseudoranges_iter++) gnss_pseudoranges_iter++)
{ {
double pr = gnss_pseudoranges_iter->second.Pseudorange_m; double pr = gnss_pseudoranges_iter->second.Pseudorange_m;
pseudoranges[gnss_pseudoranges_iter->first] = pr; pseudoranges[gnss_pseudoranges_iter->first] = pr;
} }
// ############ 1. READ EPHEMERIS FROM QUEUE ###################### // ############ 1. READ EPHEMERIS FROM QUEUE ######################
// find the minimum index (nearest satellite, will be the reference) // find the minimum index (nearest satellite, will be the reference)
gnss_pseudoranges_iter = std::min_element(gnss_pseudoranges_map.begin(), gnss_pseudoranges_map.end(), pseudoranges_pairCompare_min); gnss_pseudoranges_iter = std::min_element(gnss_pseudoranges_map.begin(), gnss_pseudoranges_map.end(), pseudoranges_pairCompare_min);
Gps_Navigation_Message nav_msg; Gps_Navigation_Message nav_msg;
while (d_nav_queue->try_pop(nav_msg) == true) while (d_nav_queue->try_pop(nav_msg) == true)
{ {
std::cout<<"New ephemeris record has arrived from SAT ID " std::cout << "New ephemeris record has arrived from SAT ID "
<< nav_msg.i_satellite_PRN << " (Block " << nav_msg.i_satellite_PRN << " (Block "
<< nav_msg.satelliteBlock[nav_msg.i_satellite_PRN] << nav_msg.satelliteBlock[nav_msg.i_satellite_PRN]
<< ")" << std::endl; << ")" << std::endl;
d_last_nav_msg = nav_msg; d_last_nav_msg = nav_msg;
if (nav_msg.b_valid_ephemeris_set_flag==true) if (nav_msg.b_valid_ephemeris_set_flag == true)
{ {
d_ls_pvt->d_ephemeris[nav_msg.i_channel_ID] = nav_msg; d_ls_pvt->d_ephemeris[nav_msg.i_channel_ID] = nav_msg;
nav_data_map[nav_msg.i_channel_ID] = nav_msg; nav_data_map[nav_msg.i_channel_ID] = nav_msg;
} }
// **** update pseudoranges clock **** // **** update pseudoranges clock ****
if (nav_msg.i_satellite_PRN == gnss_pseudoranges_iter->second.PRN) if (nav_msg.i_satellite_PRN == gnss_pseudoranges_iter->second.PRN)
{ {
d_ephemeris_clock_s = d_last_nav_msg.d_TOW; d_ephemeris_clock_s = d_last_nav_msg.d_TOW;
d_ephemeris_timestamp_ms = d_last_nav_msg.d_subframe_timestamp_ms; d_ephemeris_timestamp_ms = d_last_nav_msg.d_subframe_timestamp_ms;
} }
} }
// ############ 2. COMPUTE THE PVT ################################ // ############ 2. COMPUTE THE PVT ################################
// write the pseudoranges to RINEX OBS file // write the pseudoranges to RINEX OBS file
// 1- need a valid clock // 1- need a valid clock
if (d_ephemeris_clock_s > 0 and d_last_nav_msg.i_satellite_PRN > 0 and d_last_nav_msg.b_valid_ephemeris_set_flag==true) if (d_ephemeris_clock_s > 0 and d_last_nav_msg.i_satellite_PRN > 0 and d_last_nav_msg.b_valid_ephemeris_set_flag == true)
{ {
double clock_error; double clock_error;
double satellite_tx_time_using_timestamps; double satellite_tx_time_using_timestamps;
//for GPS L1 C/A: t_tx=TOW+N_symbols_from_TOW*T_symbol //for GPS L1 C/A: t_tx = TOW + N_symbols_from_TOW*T_symbol
//Notice that the TOW is decoded AFTER processing the subframe -> we ned to add ONE subframe duration to t_tx //Notice that the TOW is decoded AFTER processing the subframe -> we need to add ONE subframe duration to t_tx
d_tx_time=d_ephemeris_clock_s + gnss_pseudoranges_iter->second.Pseudorange_symbol_shift/(double)GPS_CA_TELEMETRY_RATE_SYMBOLS_SECOND+GPS_SUBFRAME_SECONDS; d_tx_time = d_ephemeris_clock_s + gnss_pseudoranges_iter->second.Pseudorange_symbol_shift/(double)GPS_CA_TELEMETRY_RATE_SYMBOLS_SECOND + GPS_SUBFRAME_SECONDS;
//Perform an extra check to verify the TOW update (the ephemeris queue is ASYNCHRONOUS to the GNU Radio Gnss_Synchro sample stream) //Perform an extra check to verify the TOW update (the ephemeris queue is ASYNCHRONOUS to the GNU Radio Gnss_Synchro sample stream)
//-> compute the t_tx_timestamps using the symbols timestamp (it is affected by code Doppler, but it is not wrapped like N_symbols_from_TOW) //-> compute the t_tx_timestamps using the symbols timestamp (it is affected by code Doppler, but it is not wrapped like N_symbols_from_TOW)
satellite_tx_time_using_timestamps=d_ephemeris_clock_s + (gnss_pseudoranges_iter->second.Pseudorange_timestamp_ms-d_ephemeris_timestamp_ms)/1000.0; satellite_tx_time_using_timestamps = d_ephemeris_clock_s + (gnss_pseudoranges_iter->second.Pseudorange_timestamp_ms - d_ephemeris_timestamp_ms)/1000.0;
//->compute the absolute error between both T_tx //->compute the absolute error between both T_tx
clock_error=std::abs(d_tx_time-satellite_tx_time_using_timestamps); clock_error = std::abs(d_tx_time - satellite_tx_time_using_timestamps);
// -> The symbol conter N_symbols_from_TOW will be resetted every new received telemetry word, if the TOW is not uptated, both t_tx and t_tx_timestamps times will difer by more than 1 seconds. // -> The symbol counter N_symbols_from_TOW will be reset every new received telemetry word, if the TOW is not updated, both t_tx and t_tx_timestamps times will difer by more than 1 seconds.
if (clock_error<1){ if (clock_error < 1)
// compute on the fly PVT solution {
//mod 8/4/2012 Set the PVT computation rate in this block // compute on the fly PVT solution
if ((d_sample_counter % d_output_rate_ms) == 0) //mod 8/4/2012 Set the PVT computation rate in this block
{ if ((d_sample_counter % d_output_rate_ms) == 0)
{
if (d_ls_pvt->get_PVT(gnss_pseudoranges_map,d_tx_time,d_flag_averaging) == true) if (d_ls_pvt->get_PVT(gnss_pseudoranges_map,d_tx_time,d_flag_averaging) == true)
{ {
d_kml_dump.print_position(d_ls_pvt, d_flag_averaging); d_kml_dump.print_position(d_ls_pvt, d_flag_averaging);
@ -225,43 +226,42 @@ int gps_l1_ca_pvt_cc::general_work (int noutput_items, gr_vector_int &ninput_ite
rp->log_rinex_obs(rp->obsFile, d_last_nav_msg, pseudoranges); rp->log_rinex_obs(rp->obsFile, d_last_nav_msg, pseudoranges);
} }
} }
} }
if (((d_sample_counter % d_display_rate_ms) == 0) and d_ls_pvt->b_valid_position==true) if (((d_sample_counter % d_display_rate_ms) == 0) and d_ls_pvt->b_valid_position == true)
{ {
std::cout << "Position at " << boost::posix_time::to_simple_string(d_ls_pvt->d_position_UTC_time) std::cout << "Position at " << boost::posix_time::to_simple_string(d_ls_pvt->d_position_UTC_time)
<< " is Lat = " << d_ls_pvt->d_latitude_d << " [deg], Long = " << d_ls_pvt->d_longitude_d << " is Lat = " << d_ls_pvt->d_latitude_d << " [deg], Long = " << d_ls_pvt->d_longitude_d
<< " [deg], Height= " << d_ls_pvt->d_height_m << " [m]" << std::endl; << " [deg], Height= " << d_ls_pvt->d_height_m << " [m]" << std::endl;
std::cout << "Dilution of Precision at " << boost::posix_time::to_simple_string(d_ls_pvt->d_position_UTC_time)
<< " is HDOP = " << d_ls_pvt->d_HDOP << " and VDOP = " << d_ls_pvt->d_VDOP << std::endl;
}
if(d_dump == true) std::cout << "Dilution of Precision at " << boost::posix_time::to_simple_string(d_ls_pvt->d_position_UTC_time)
{ << " is HDOP = " << d_ls_pvt->d_HDOP << " and VDOP = " << d_ls_pvt->d_VDOP << std::endl;
// MULTIPLEXED FILE RECORDING - Record results to file }
try
{
double tmp_double;
for (unsigned int i=0; i<d_nchannels ; i++)
{
tmp_double = in[i][0].Pseudorange_m;
d_dump_file.write((char*)&tmp_double, sizeof(double));
tmp_double = in[i][0].Pseudorange_symbol_shift;
d_dump_file.write((char*)&tmp_double, sizeof(double));
d_dump_file.write((char*)&d_tx_time, sizeof(double));
}
}
catch (std::ifstream::failure e)
{
std::cout << "Exception writing observables dump file " << e.what() << std::endl;
}
}
} if(d_dump == true)
} {
// MULTIPLEXED FILE RECORDING - Record results to file
consume_each(1); //one by one try
return 0; {
double tmp_double;
for (unsigned int i=0; i<d_nchannels ; i++)
{
tmp_double = in[i][0].Pseudorange_m;
d_dump_file.write((char*)&tmp_double, sizeof(double));
tmp_double = in[i][0].Pseudorange_symbol_shift;
d_dump_file.write((char*)&tmp_double, sizeof(double));
d_dump_file.write((char*)&d_tx_time, sizeof(double));
}
}
catch (std::ifstream::failure e)
{
std::cout << "Exception writing observables dump file " << e.what() << std::endl;
}
}
}
}
consume_each(1); //one by one
return 0;
} }

File diff suppressed because it is too large Load Diff

View File

@ -57,12 +57,12 @@ class gps_l1_ca_ls_pvt
{ {
private: private:
arma::vec leastSquarePos(arma::mat satpos, arma::vec obs, arma::mat w); arma::vec leastSquarePos(arma::mat satpos, arma::vec obs, arma::mat w);
arma::vec e_r_corr(double traveltime, arma::vec X_sat); arma::vec rotateSatellite(double traveltime, arma::vec X_sat);
void topocent(double *Az, double *El, double *D, arma::vec x, arma::vec x_sat); void topocent(double *Az, double *El, double *D, arma::vec x, arma::vec dx);
void togeod(double *dphi, double *dlambda, double *h, double a, double finv, double X, double Y, double Z); void togeod(double *dphi, double *dlambda, double *h, double a, double finv, double X, double Y, double Z);
public: public:
int d_nchannels; //! Number of available channels for positioning int d_nchannels; //! Number of available channels for positioning
int d_valid_observations; //! Number of valid pseudorrange observations (valid satellites) int d_valid_observations; //! Number of valid pseudorange observations (valid satellites)
int d_visible_satellites_IDs[PVT_MAX_CHANNELS]; //! Array with the IDs of the valid satellites int d_visible_satellites_IDs[PVT_MAX_CHANNELS]; //! Array with the IDs of the valid satellites
double d_visible_satellites_El[PVT_MAX_CHANNELS]; //! Array with the LOS Elevation of the valid satellites double d_visible_satellites_El[PVT_MAX_CHANNELS]; //! Array with the LOS Elevation of the valid satellites
double d_visible_satellites_Az[PVT_MAX_CHANNELS]; //! Array with the LOS Azimuth of the valid satellites double d_visible_satellites_Az[PVT_MAX_CHANNELS]; //! Array with the LOS Azimuth of the valid satellites
@ -121,7 +121,7 @@ public:
* \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.