Rinex3ObsFileLoader.cpp
Go to the documentation of this file.
1 //==============================================================================
2 //
3 // This file is part of GNSSTk, the ARL:UT GNSS Toolkit.
4 //
5 // The GNSSTk is free software; you can redistribute it and/or modify
6 // it under the terms of the GNU Lesser General Public License as published
7 // by the Free Software Foundation; either version 3.0 of the License, or
8 // any later version.
9 //
10 // The GNSSTk is distributed in the hope that it will be useful,
11 // but WITHOUT ANY WARRANTY; without even the implied warranty of
12 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 // GNU Lesser General Public License for more details.
14 //
15 // You should have received a copy of the GNU Lesser General Public
16 // License along with GNSSTk; if not, write to the Free Software Foundation,
17 // Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110, USA
18 //
19 // This software was developed by Applied Research Laboratories at the
20 // University of Texas at Austin.
21 // Copyright 2004-2022, The Board of Regents of The University of Texas System
22 //
23 //==============================================================================
24 
25 //==============================================================================
26 //
27 // This software was developed by Applied Research Laboratories at the
28 // University of Texas at Austin, under contract to an agency or agencies
29 // within the U.S. Department of Defense. The U.S. Government retains all
30 // rights to use, duplicate, distribute, disclose, or release this software.
31 //
32 // Pursuant to DoD Directive 523024
33 //
34 // DISTRIBUTION STATEMENT A: This software has been approved for public
35 // release, distribution is unlimited.
36 //
37 //==============================================================================
38 
43 //------------------------------------------------------------------------------------
44 // system includes
45 #include <iostream>
46 
47 // GNSSTk
48 #include "Exception.hpp"
49 #include "GPSWeekSecond.hpp"
50 #include "MostCommonValue.hpp"
51 #include "Rinex3ObsData.hpp"
52 #include "Rinex3ObsHeader.hpp"
53 #include "Rinex3ObsStream.hpp"
54 #include "StringUtils.hpp"
55 #include "TimeString.hpp" // printTime
56 
57 // geomatics
58 #include "GSatID.hpp" // for SatPass
59 #include "Rinex3ObsFileLoader.hpp"
60 #include "logstream.hpp" // TEMP
61 
62 using namespace std;
63 
64 namespace gnsstk
65 {
66 
67  //---------------------------------------------------------------------------------
68  const double Rinex3ObsFileLoader::dttol(0.001);
69 
70  //---------------------------------------------------------------------------------
71  /* Read the files already defined
72  param[out] errmsg an error/warning message, blank for success
73  param[out] msg an informative message
74  return 0 ok, >0 number of files read */
75  int Rinex3ObsFileLoader::loadFiles(string& errmsg, string& msg)
76  {
77  try
78  {
79  int nint;
80  unsigned int i, j;
81  double dt;
82  string str;
83 
84  /* current latest RINEX version
85  critical to ObsID identification independent of RINEX version */
86  const double currVer(Rinex3ObsBase::currentVersion);
87 
88  /* Rinex3ObsHeader from Rinex3ObsHeader class GNSSTk class
89  roh = rinex obs header */
90  Rinex3ObsHeader roh;
91  /* Rinex3ObsData from Rinex3ObsData class in GNSSTk
92  rod = rinex obs data, and outrod = output rinex obs data? */
93  Rinex3ObsData rod, outrod;
94  vector<string>::const_iterator vit;
95  map<RinexSatID, vector<int>>::iterator soit; // SatObsCountMap
96  ostringstream oss, ossx;
97 
99  // setTimeSystem sets the method for internal variable m_timeSystem
100  prevtime.setTimeSystem(TimeSystem::Any);
101 
102  /* read the files
103  initialize number read counter to zero */
104  int nread(0);
105  // loop over file names
106  for (unsigned int nf = 0; nf < filenames.size(); nf++)
107  {
108  // set the file name to a particular string
109  string filename(filenames[nf]);
110  // strip any blank values from beginning of file name
111  StringUtils::stripLeading(filename);
112  // strip any blank values from end of file name
113  StringUtils::stripTrailing(filename);
114  // If the file name list is empty, then an error in the file name
115  if (filename.empty())
116  {
117  oss << "Error - file name " << nf + 1 << " is blank";
118  continue;
119  }
120 
121  // declare and initialize onOrder to false
122  bool onOrder(false);
123  vector<int> nOrder;
124  vector<CommonTime> timeOrder;
125 
126  // read one file
127  for (;;)
128  {
129  /* open file ---------------------------------------------
130  converts file name from a string to a vector of characters
131  using c_str */
132  Rinex3ObsStream strm(filename.c_str());
133  // if the obs stream is not successfully opened
134  if (!strm.is_open())
135  {
136  oss << "Error - could not open file " << filename << endl;
137  break;
138  }
139  strm.exceptions(fstream::failbit);
140 
141  // read header -------------------------------------------
142  try
143  {
144  strm >> roh;
145 
146  /* update list of wanted obs types
147  create iterator for looping through roh.mapObsTypes
148  make it a const_iterator, so that it can be used for access
149  only, and cannot be used for modification the
150  roh.mapObsTypes is of type RinexObsMap, which has format
151  map<string,RinexObsVec> == map<string,vector<RinexObsID>>
152  A map where string values are the keys and
153  vector<RinexObsID> are the values mapped to those strings */
154  map<string, vector<RinexObsID>>::const_iterator kt;
155  for (kt = roh.mapObsTypes.begin();
156  kt != roh.mapObsTypes.end(); kt++)
157  {
158  for (i = 0; i < kt->second.size(); i++)
159  {
160  // need 4-char string version of ObsID
161  string sys = kt->first; // system
162  string rot =
163  kt->second[i].asString(currVer); // 3-char id
164  string srot = sys + rot; // 4-char id
165  string code = rot.substr(2, 1); // tracking code
166 
167  /* is this ObsID Wanted? and should it be added?
168  NB RinexObsID::operator==() handles '*' but does not
169  compare sys NB input (loadObsID()) checks validity of
170  ObsIDs */
171 
172  for (j = 0; j < inputWantedObsTypes.size(); j++)
173  {
174  if (vectorindex(wantedObsTypes, srot) != -1)
175  {
176  continue; // already there
177  }
178 
179  // wsrot = wanted string rinex obs type
180  string wsrot(inputWantedObsTypes[j]);
181 
182  string wsys(wsrot.substr(0, 1));
183  if (wsys != "*" && wsys != sys) // different systems
184  {
185  continue;
186  }
187 
188  string wcode(wsrot.substr(3, 1));
189  if (wcode != "*" && wcode != code) // different codes
190  {
191  continue;
192  }
193 
194  if (wsrot.substr(1, 2) !=
195  rot.substr(0, 2)) // diff type-freq
196  {
197  continue;
198  }
199 
200  // ok add it
201  wantedObsTypes.push_back(srot); // add it
202  // the number of observations for each observation type
203  countWantedObsTypes.push_back(0);
204 
205  ossx << " Add obs type " << srot << " =~ "
206  << inputWantedObsTypes[j] << " from "
207  << filename << endl;
208  }
209  }
210  } // end loop over obs types in header
211 
212  // must keep SatObsCountMap vectors parallel to wantedObsTypes
213  if (SatObsCountMap.size() > 0)
214  { // table exists
215  vector<int> v(SatObsCountMap.begin()->second);
216  j = wantedObsTypes.size();
217  if (v.size() < j)
218  { // vectors are short
219  soit = SatObsCountMap.begin();
220  for (; soit != SatObsCountMap.end(); ++soit)
221  soit->second.resize(j, 0); // extend with zeros
222  }
223  }
224 
225  headers.push_back(roh);
226  }
227  catch (Exception& e)
228  {
229  oss << "Error - failed to read header for file " << filename
230  << " with exception " << e.getText(0) << endl;
231  strm.close();
232  break;
233  }
234 
235  /* loop over epochs --------------------------------------
236  while(1) always true, so only breaks out of loop with a break
237  statement */
238  while (1)
239  {
240  try
241  {
242  strm >> rod;
243  rod.time.setTimeSystem(TimeSystem::Any);
244  }
245  catch (Exception& e)
246  {
247  oss << "Error - failed to read data in file " << filename
248  << " with exception " << e.getText(0) << endl;
249  break;
250  }
251 
252  // EOF or error
253  if (strm.eof() || !strm.good())
254  {
255  break;
256  }
257 
258  // skip aux header, etc
259  if (rod.epochFlag != 0 && rod.epochFlag != 1)
260  {
261  continue;
262  }
263 
264  // decimate to dtdec-even sec-of-week
265  if (dtdec > 0.0)
266  {
267  double sow(static_cast<GPSWeekSecond>(rod.time).sow);
268  // LOG(INFO) << fixed << setprecision(3) << "Dt " << dt
269  //<< " dtdec " << dtdec << " sow " << sow
270  //<< " test " << ::fabs(sow-dtdec*long(0.5+sow/dtdec));
271  if (::fabs(sow - dtdec * long(0.5 + sow / dtdec)) > 0.5)
272  {
273  continue;
274  }
275  }
276 
277  // consider timestep
278  if (prevtime != CommonTime::BEGINNING_OF_TIME)
279  {
280  // compute time since the previous epoch
281  dt = rod.time - prevtime;
282 
283  if (dt >= dttol)
284  { // positive dt only
285  // add to the timestep estimator
286  mcv.add(dt);
287  }
288  else if (dt < dttol)
289  { // negative, and positive but tiny (< dttol)
290  // if(isLenient) {
291  if (!onOrder)
292  {
293  nOrder.push_back(0);
294  timeOrder.push_back(prevtime);
295  onOrder = true;
296  }
297  nOrder[nOrder.size() - 1]++;
298  continue;
299  //}
300  // GNSSTK_THROW(Exception(string("Records out of time
301  // order: dt ")
302  // + StringUtils::asString<double>(dt) + string(" at
303  // time ")
304  // + printTime(rod.time,timefmt)));
305  }
306  onOrder = false;
307  }
308 
309  // set previous time to current time
310  prevtime = rod.time;
311  // ignore data outside of time limits given by user
312  if (rod.time < startTime)
313  {
314  continue;
315  }
316  if (rod.time > stopTime)
317  {
318  break;
319  }
320  if (rod.time < begDataTime)
321  {
322  begDataTime = rod.time;
323  }
324  if (rod.time > endDataTime)
325  {
326  endDataTime = rod.time;
327  }
328 
329  // The integer number of epochs is advanced
330  nepochs++;
331  if (nepochsToRead > -1 && nepochs >= nepochsToRead)
332  {
333  break;
334  }
335 
336  // prepare output rod
337  outrod.time = rod.time;
338  outrod.clockOffset = rod.clockOffset;
339  outrod.epochFlag = rod.epochFlag;
340  //?? outrod.auxHeader.clear();
341  outrod.numSVs = 0;
342  outrod.obs.clear();
343 
344  // loop over satellites, counting data per ObsID
345  Rinex3ObsData::DataMap::const_iterator it;
346  for (it = rod.obs.begin(); it != rod.obs.end(); ++it)
347  {
348  /* Create new RinexSatID variable called sat, initialize
349  with the it->first pointer from rod.obs current
350  iteration */
351  RinexSatID sat(it->first);
352 
353  /* is the sat excluded? NB it does not exclude
354  sat=(sys,-1) */
355  if (exSats.size() > 0 && find(exSats.begin(), exSats.end(),
356  sat) != exSats.end())
357  {
358  continue;
359  }
360 
361  /* Exract GNSS system from sat ID, creating new string
362  variable sys */
363  string sys(sat.toString().substr(0, 1));
364  /* Extract the observation types from the rinex obs header
365  object roh corresponding to the GNSS system from the sat
366  ID, creating new RinexObsID vector types */
367  const vector<RinexObsID> types(roh.mapObsTypes[sys]);
368 
369  // loop over obs
370  for (i = 0; i < it->second.size(); i++)
371  {
372  /* if the obs data is equal to zero, then do not
373  consider that obs value (equivalent to missing data) */
374  if (it->second[i].data == 0.0)
375  {
376  continue; // don't count missing
377  }
378 
379  /* combine the system and obs type into total rinex obs
380  ID */
381  string srot = sys + types[i].asString(
382  currVer); // 4-char RinexObsID
383 
384  /* is it wanted? nint is the index into
385  wantedObsTypes, SatObsCountMap and outrod.obs
386  vectorindex returns the index of the value srot in
387  wantedObsTypes if it doesn't exist in that vector,
388  return -1 */
389  nint = vectorindex(wantedObsTypes, srot);
390  if (nint == -1)
391  {
392  continue;
393  }
394 
395  /* count the sat/obs
396  map<RinexSatID, std::vector<int>> */
397  soit = SatObsCountMap.find(sat);
398  if (soit == SatObsCountMap.end())
399  { // add the sat
400  vector<int> v(wantedObsTypes.size(),
401  0); // keep parallel
402  SatObsCountMap[sat] = v; // creates map entry
403  }
404  SatObsCountMap[sat][nint]++;
405  countWantedObsTypes[nint]++;
406 
407  // add it to outrod
408  if (saveData)
409  {
410  // if the satellite is not in outrod.obs
411  if (outrod.obs.find(sat) == outrod.obs.end())
412  {
413  vector<RinexDatum> v(wantedObsTypes.size());
414  outrod.obs[sat] = v;
415  outrod.numSVs++;
416  }
417  outrod.obs[sat][nint] = it->second[i];
418  }
419  }
420  }
421 
422  // if saving data, save
423  if (saveData && outrod.obs.size() > 0)
424  {
425  datastore.push_back(outrod);
426  }
427 
428  } // end loop over epochs
429 
430  // time steps
431  rawdt = mcv.bestDT();
432  nominalDT =
433  (dtdec > 0.0 ? (dtdec > rawdt ? dtdec : rawdt) : rawdt);
434 
435  strm.close();
436 
437  break; // mandatory
438  } // end for(;;)
439 
440  nread++;
441 
442  // warn of time order problems
443  if (timeOrder.size() > 0)
444  {
445  for (i = 0; i < timeOrder.size(); i++)
446  oss << "Warning - in file " << filename << " " << nOrder[i]
447  << " data records following epoch "
448  << printTime(timeOrder[i], timefmt)
449  << " are out of time order" << endl;
450  }
451 
452  if (nepochsToRead > -1 && nepochs >= nepochsToRead)
453  {
454  break;
455  }
456 
457  } // end loop over files
458 
459  if (!errmsg.empty())
460  {
461  errmsg += string("\n");
462  }
463  errmsg += oss.str();
464  if (!errmsg.empty())
465  {
466  StringUtils::stripTrailing(errmsg, '\n');
467  StringUtils::stripTrailing(errmsg, '\r');
468  }
469  msg = ossx.str();
470  if (!msg.empty())
471  {
472  StringUtils::stripTrailing(msg, '\n');
473  StringUtils::stripTrailing(msg, '\r');
474  }
475 
476  return nread;
477  }
478  catch (Exception& e)
479  {
480  GNSSTK_RETHROW(e);
481  }
482  catch (exception& e)
483  {
484  Exception E("std except: " + string(e.what()));
485  GNSSTK_THROW(E);
486  }
487  catch (...)
488  {
489  Exception e("Unknown exception");
490  GNSSTK_THROW(e);
491  }
492  }
493 
494  //---------------------------------------------------------------------------------
496  {
497  int i;
498  static const string longfmt("%04Y/%02m/%02d %02H:%02M:%02S %4F %10.3g");
499  ostringstream oss;
500  oss << "Summary of input RINEX obs data files (" << filenames.size()
501  << "):\n";
502  for (i = 0; i < filenames.size(); i++)
503  oss << (i == 0 ? " RINEX obs file: " : " ")
504  << filenames[i] << endl;
505  oss << " Interval " << fixed << setprecision(2) << getDT()
506  << "sec, obs types";
507  for (i = 0; i < wantedObsTypes.size(); i++)
508  oss << " " << wantedObsTypes[i];
509  oss << ", store size " << datastore.size();
510  oss << "\n";
511  oss << " Time limits: begin " << printTime(begDataTime, longfmt) << "\n"
512  << " end " << printTime(endDataTime, longfmt) << "\n";
513 
514  dumpSatObsTable(oss);
515 
516  oss << "End of summary";
517 
518  return oss.str();
519  }
520 
521  //---------------------------------------------------------------------------------
522  /* Write the stored data to a list of SatPass objects, given a vector of
523  obstypes and (for each system) a parallel vector of indexes into the
524  Loader's ObsIDs (getWantedObsTypes()), and a vector of SatPass to be
525  written to. SPList need not be empty; however if not empty, obstypes must
526  be identical to those of existing SatPasses. param[in] sysSPOT map of
527  <sys,vector<ObsID>> for SatPass (2-char obsID) param[in] indexLoadOT
528  map<char,vector<int>> with key=system char,
529  value=vector parallel to obstypes with elements equal to
530  {index in loader's ObsIDs for each obstype, or -1 if not in loader}
531  param[in,out] SPList vector of SatPass to which data store is written
532  return >0 number of passes created, -1 inconsistent input, -2 obstypes
533  inconsistent with existing SatPass, -3 Loader not configured to save data,
534  -4 no data -5 obstypes not provided for all systems */
535  int Rinex3ObsFileLoader::WriteSatPassList(
536  const map<char, vector<string>>& sysSPOT,
537  const map<char, vector<int>>& indexLoadOT, vector<SatPass>& SPList)
538  {
539  try
540  {
541  if (!dataSaved())
542  {
543  return -3;
544  }
545  if (datastore.size() == 0)
546  {
547  return -4;
548  }
549 
550  char sys;
551  int npass(0);
552  unsigned int i;
553  unsigned short flag;
554  GSatID sat;
555  map<GSatID, unsigned int> indexForSat;
556  // satellite iterator
557  map<GSatID, unsigned int>::const_iterator satit;
558  // observation iterator
559  map<char, vector<string>>::const_iterator obsit;
560 
561  // add to existing SPList
562  if (SPList.size() > 0)
563  {
564  // sort existing list on time - this probably already done
565  std::sort(SPList.begin(), SPList.end());
566 
567  // fill index array using SPList - later ones overwrite earlier ones
568  for (i = 0; i < SPList.size(); i++)
569  indexForSat[SPList[i].getSat()] = i;
570  }
571 
572  // for use in putting data into SatPass
573  // initialize observation iterator
574  obsit = sysSPOT.begin();
575  // initialize/determine number of observations, from input sysSPOT map
576  const int nobs(obsit->second.size());
577  vector<double> data(nobs, 0.0);
578  vector<unsigned short> ssi(nobs, 0), lli(nobs, 0);
579 
580  // loop over the data store = vector<Rinex3ObsData>
581  for (unsigned int nds = 0; nds < datastore.size(); nds++)
582  {
583 
584  // LOG(INFO) << "WriteSPL " <<
585  // printTime(datastore[nds].time,timefmt)
586  //<< " Nsats " << datastore[nds].obs.size();
587  // dumpStoreEpoch(LOGstrm,datastore[nds]);
588 
589  // loop over satellites
590  Rinex3ObsData::DataMap::const_iterator it;
591  map<char, vector<int>>::const_iterator jt;
592  for (it = datastore[nds].obs.begin();
593  it != datastore[nds].obs.end(); ++it)
594  {
595  sys = it->first.systemChar();
596  jt = indexLoadOT.find(sys);
597  if (jt == indexLoadOT.end()) // skip unwanted system
598  {
599  continue;
600  }
601  sat = GSatID(it->first); // converts from RinexSatID
602 
603  // get obstypes for this sys
604  obsit = sysSPOT.find(sys);
605  if (obsit == sysSPOT.end()) // sysSPOT not found for system sys
606  {
607  return -5;
608  }
609 
610  // pull data out of store and put in arrays
611  flag = SatPass::OK;
612  for (i = 0; i < jt->second.size(); i++)
613  {
614  int ind = jt->second[i];
615  if (ind < 0)
616  {
617  data[i] = 0.0;
618  ssi[i] = lli[i] = 0;
619  // don't flag BAD as there may be empty obs types in this
620  // SatPass
621  }
622  else
623  {
624  data[i] = it->second[ind].data;
625  ssi[i] = it->second[ind].ssi;
626  lli[i] = it->second[ind].lli;
627  // NB so one bad obs makes the sat/epoch bad
628  // TD does loader keep epochs with no good data?
629  if (::fabs(data[i]) < 1.e-8)
630  {
631  flag = SatPass::BAD;
632  }
633  }
634  // LOG(INFO) << " ind " << ind << " SPOT " << obsit->second[i]
635  //<< " R3OT " << (ind >= 0 ? wantedObsTypes[ind]:"NA")
636  //<< " sat " << sat
637  //<< " data " << fixed << setprecision(4)
638  //<< (ind >= 0 ? it->second[ind].data : 0.0) << "/"
639  //<< (ind >= 0 ? it->second[ind].ssi : 0) << "/"
640  //<< (ind >= 0 ? it->second[ind].lli : 0) << " flag " << flag;
641  }
642 
643  // find the current SatPass for this sat
644  satit = indexForSat.find(sat);
645  if (satit == indexForSat.end())
646  { // create a new one
647  SatPass newSP(sat, nominalDT, obsit->second);
648  SPList.push_back(newSP);
649  npass++;
650  indexForSat[sat] = SPList.size() - 1;
651  satit = indexForSat.find(sat);
652  }
653 
654  // add the data to the SatPass
655  do
656  {
657  i = SPList[satit->second].addData(
658  datastore[nds].time, obsit->second, data, lli, ssi, flag);
659 
660  if (i == -1)
661  { // there was a gap - break into two passes
662  SatPass newSP(sat, nominalDT, obsit->second);
663  SPList.push_back(newSP);
664  npass++;
665  indexForSat[sat] = SPList.size() - 1;
666  satit = indexForSat.find(sat);
667  }
668 
669  } while (i == -1); // will iterate only once, if there is a gap
670 
671  } // end loop over satellites
672 
673  } // end loop over data store
674 
675  return npass;
676  }
677  catch (Exception& e)
678  {
679  GNSSTK_RETHROW(e);
680  }
681  }
682 
683  //---------------------------------------------------------------------------------
684  //---------------------------------------------------------------------------------
685  /* Dump the SatObsCount table
686  param ostream s to which to write the table */
687  void Rinex3ObsFileLoader::dumpSatObsTable(ostream& s) const
688  {
689  unsigned int i;
690 
691  // dump the obs types
692  s << "Table of Sat/Obs counts\n ";
693  for (i = 0; i < wantedObsTypes.size(); i++)
694  s << " " << setw(5) << wantedObsTypes[i];
695  s << endl;
696 
697  // dump the counts
698  map<RinexSatID, vector<int>>::const_iterator soit;
699  for (soit = SatObsCountMap.begin(); soit != SatObsCountMap.end(); ++soit)
700  {
701  s << " " << soit->first;
702  for (i = 0; i < soit->second.size(); i++)
703  s << " " << setw(5) << soit->second[i];
704  s << endl;
705  }
706 
707  s << " TOT";
708  for (i = 0; i < countWantedObsTypes.size(); i++)
709  s << " " << setw(5) << countWantedObsTypes[i];
710  s << " total " << nepochs << " epochs" << endl;
711  }
712 
713  //---------------------------------------------------------------------------------
714  /* Dump the stored data at one epoch - NB setTimeFormat()
715  param ostream s to which to write */
716  void Rinex3ObsFileLoader::dumpStoreEpoch(ostream& s,
717  const Rinex3ObsData& rod) const
718  {
719  s << "Dump of Rinex3ObsData"
720  << " at " << printTime(rod.time, timefmt)
721  << " epochFlag = " << rod.epochFlag << " numSVs = " << rod.numSVs
722  << fixed << setprecision(9) << " clk offset = " << rod.clockOffset
723  << endl;
724 
725  if (rod.epochFlag == 0 || rod.epochFlag == 1)
726  {
727  Rinex3ObsData::DataMap::const_iterator jt;
728  for (jt = rod.obs.begin(); jt != rod.obs.end(); jt++)
729  {
730  s << " " << jt->first.toString() << ":" << fixed << setprecision(3);
731  for (unsigned int j = 0; j < jt->second.size(); j++)
732  {
733  s << " " << setw(13) << jt->second[j].data << "/"
734  << jt->second[j].lli << "/" << jt->second[j].ssi << "/"
735  << wantedObsTypes[j];
736  }
737  s << endl;
738  }
739  }
740  else
741  {
742  s << "aux. header info:" << endl;
743  rod.auxHeader.dump(s);
744  }
745  }
746 
747  //---------------------------------------------------------------------------------
748  /* Dump the stored data - NB setTimeFormat()
749  param ostream s to which to write */
750  void Rinex3ObsFileLoader::dumpStoreData(ostream& s) const
751  {
752  s << "\nDump the ROFL data(" << datastore.size() << "):" << endl;
753  for (unsigned int i = 0; i < datastore.size(); i++)
754  {
755  const Rinex3ObsData &rod(datastore[i]);
756  dumpStoreEpoch(s, rod);
757  }
758  }
759 
760  //---------------------------------------------------------------------------------
761  //---------------------------------------------------------------------------------
762  /* dump a table of all valid RinexObsIDs
763  param ostream s to which to write the table */
764  void dumpAllRinex3ObsTypes(ostream& os)
765  {
766  using namespace gnsstk::StringUtils;
767 
768  // windows compiler truncates long names (!)
769  typedef map<string, map<string, map<string, map<char, string>>>> tableMap;
770  typedef map<string, map<string, map<char, string>>> obsMap;
771  typedef map<string, map<char, string>> codeMap;
772 
773  vector<string> goodtags;
774  string syss(RinexObsID::validRinexSystems);
775  /* build a table: table[sys][band][codedesc][type] = 4-char ObsID;
776  char cb.. tc.. ot.. */
777  tableMap table;
778  for (size_t s = 0; s < syss.size(); s++)
779  {
780  for (CarrierBand j : CarrierBandIterator())
781  {
783  {
785  {
786  try
787  {
788  string tag(string(1, syss[s]) +
789  string(1, RinexObsID::ot2char[i]) +
790  string(1, RinexObsID::cb2char[j]) +
791  string(1, RinexObsID::tc2char[k]));
792  RinexObsID obs(tag, Rinex3ObsBase::currentVersion);
793  string name(asString(obs));
794  if (name.find("Unknown") != string::npos ||
795  name.find("undefined") != string::npos ||
796  name.find("Any") != string::npos ||
797  !isValidRinexObsID(tag))
798  {
799  continue;
800  }
801 
802  if (find(goodtags.begin(), goodtags.end(), tag) ==
803  goodtags.end())
804  {
805  goodtags.push_back(tag);
806  string sys(
807  RinexSatID(string(1, tag[0])).systemString3());
808  char type(RinexObsID::ot2char[i]);
809  string id(tag); // TD keep sys char ? id(tag.substr(1));
810  string desc(asString(
811  RinexObsID(tag, Rinex3ObsBase::currentVersion)));
812  vector<string> fld(split(desc, ' '));
813  string codedesc(fld[1].substr(syss[s] == 'S' ? 4 : 3));
814  string band(fld[0]);
815  table[sys][band][codedesc][type] = id;
816  }
817  }
818  catch (InvalidParameter& )
819  {
820  continue;
821  }
822  } // for (ObservationType i : ObservationTypeIterator())
823  } // for (TrackingCode k : TrackingCodeIterator())
824  } // for (CarrierBand j : CarrierBandIterator())
825  } // for (size_t s=0; s<syss.size(); s++)
826 
827  tableMap::iterator it;
828  obsMap::iterator jt;
829  codeMap::iterator kt;
830  // find field lengths
831  size_t len2(4), len3(5), len4(6); // 3-char len4(7); // 4-char
832  for (it = table.begin(); it != table.end(); ++it)
833  {
834  for (jt = it->second.begin(); jt != it->second.end(); ++jt)
835  {
836  for (kt = jt->second.begin(); kt != jt->second.end(); ++kt)
837  {
838  if (jt->first.length() > len2)
839  {
840  len2 = jt->first.length();
841  }
842  if (kt->first.length() > len3)
843  {
844  len3 = kt->first.length();
845  }
846  }
847  }
848  }
849 
850  string fres(RinexObsID::validRinexFrequencies);
851  os << "\nAll valid RINEX3 systems : " << syss << endl;
852  os << "All valid RINEX3 frequencies : " << fres << endl;
853  os << "All valid RINEX observation codes:" << endl;
854  // (as sys+code = 1+3 char):";
855  os << " Sys " << leftJustify("Freq", len2) << " " << center("Track", len3)
856  << "Pseudo- Carrier Dopp Signal" << endl;
857  os << " " << leftJustify(" ", len2) << " " << center(" ", len3)
858  << " range phase Strength" << endl;
859 
860  // output loop
861  // looping over all valid RINEX3 systems
862  for (size_t i = 0; i < syss.size(); ++i)
863  {
864  char fr('0');
865  // Determine if this RINEX3 system is in the table
866  it = table.find(RinexSatID(string(1, syss[i])).systemString3());
867  // If not, skip this iteration of the loop
868  if (it == table.end())
869  {
870  continue;
871  }
872  // if past the first system listed, add a line break
873  if (i > 0)
874  {
875  os << endl;
876  }
877  for (jt = it->second.begin(); jt != it->second.end(); ++jt)
878  {
879  for (kt = jt->second.begin(); kt != jt->second.end(); ++kt)
880  {
881  os << " " << it->first // eg. GPS
882  << " " << leftJustify(jt->first, len2) // eg. L1
883  << " " << center(kt->first, len3) // eg. C/A
884  << " "
885  << center((kt->second['C'] == "" ? "----" : kt->second['C']),
886  len4)
887  << " "
888  << center((kt->second['L'] == "" ? "----" : kt->second['L']),
889  len4)
890  << " "
891  << center((kt->second['D'] == "" ? "----" : kt->second['D']),
892  len4)
893  << " "
894  << center((kt->second['S'] == "" ? "----" : kt->second['S']),
895  len4);
896 
897  if (fr != kt->second['L'][2])
898  {
899  fr = kt->second['L'][2];
900  string tc(RinexObsID::validRinexTrackingCodes[syss[i]][fr]);
901  if (!tc.empty())
902  {
903  os << " all codes for " << it->first << " " << jt->first
904  << " = '" << tc << "'";
905  }
906  }
907  os << endl;
908  }
909  }
910  }
911  }
912 
913 } // end namespace gnsstk
nf
int nf
Definition: IERS1996NutationData.hpp:44
gnsstk::CommonTime::add
bool add(long days, long msod, double fsod)
Definition: CommonTime.cpp:455
gnsstk::BEGINNING_OF_TIME
const Epoch BEGINNING_OF_TIME(CommonTime::BEGINNING_OF_TIME)
Earliest representable Epoch.
gnsstk::isValidRinexObsID
bool isValidRinexObsID(const std::string &strID)
Definition: RinexObsID.cpp:223
StringUtils.hpp
GSatID.hpp
gnsstk::StringUtils::center
std::string & center(std::string &s, const std::string::size_type length, const char pad=' ')
Definition: StringUtils.hpp:1607
gnsstk::Rinex3ObsHeader
Definition: Rinex3ObsHeader.hpp:155
gnsstk::CarrierBand
CarrierBand
Definition: CarrierBand.hpp:54
gnsstk::Rinex3ObsData::obs
DataMap obs
the map of observations
Definition: Rinex3ObsData.hpp:114
MostCommonValue.hpp
gnsstk::Rinex3ObsHeader::asString
static std::string asString(Field b)
Return the RINEX header label for the given field enumeration.
Definition: Rinex3ObsHeader.cpp:2761
logstream.hpp
gnsstk::StringUtils::asString
std::string asString(IonexStoreStrategy e)
Convert a IonexStoreStrategy to a whitespace-free string name.
Definition: IonexStoreStrategy.cpp:46
gnsstk::Rinex3ObsData::numSVs
short numSVs
Definition: Rinex3ObsData.hpp:109
gnsstk::SatPass
Definition: SatPass.hpp:71
gnsstk::CommonTime::setTimeSystem
CommonTime & setTimeSystem(TimeSystem timeSystem)
Definition: CommonTime.hpp:195
gnsstk::Rinex3ObsHeader::dump
virtual void dump(std::ostream &s) const
Definition: Rinex3ObsHeader.hpp:568
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::StringUtils::stripLeading
std::string & stripLeading(std::string &s, const std::string &aString, std::string::size_type num=std::string::npos)
Definition: StringUtils.hpp:1426
gnsstk::StringUtils::split
std::vector< std::string > split(const std::string &str, const char delimiter=' ')
Definition: StringUtils.hpp:2275
gnsstk::GPSWeekSecond
Definition: GPSWeekSecond.hpp:56
gnsstk::Rinex3ObsData::epochFlag
short epochFlag
Definition: Rinex3ObsData.hpp:104
gnsstk::Rinex3ObsHeader::mapObsTypes
RinexObsMap mapObsTypes
SYS / # / OBS TYPES.
Definition: Rinex3ObsHeader.hpp:519
gnsstk::CarrierBandIterator
EnumIterator< CarrierBand, CarrierBand::Unknown, CarrierBand::Last > CarrierBandIterator
Definition: CarrierBand.hpp:80
gnsstk::Exception
Definition: Exception.hpp:151
gnsstk::StringUtils::stripTrailing
std::string & stripTrailing(std::string &s, const std::string &aString, std::string::size_type num=std::string::npos)
Definition: StringUtils.hpp:1453
gnsstk::GSatID
Definition: GSatID.hpp:50
gnsstk::Exception::getText
std::string getText(const size_t &index=0) const
Definition: Exception.cpp:139
gnsstk::Rinex3ObsData::time
CommonTime time
Time corresponding to the observations.
Definition: Rinex3ObsData.hpp:91
gnsstk::TrackingCodeIterator
EnumIterator< TrackingCode, TrackingCode::Unknown, TrackingCode::Last > TrackingCodeIterator
Definition: TrackingCode.hpp:192
example4.time
time
Definition: example4.py:103
gnsstk::WeekSecond::sow
double sow
Definition: WeekSecond.hpp:155
gnsstk::Rinex3ObsData
Definition: Rinex3ObsData.hpp:75
Rinex3ObsHeader.hpp
gnsstk::RinexObsID
Definition: RinexObsID.hpp:102
Rinex3ObsData.hpp
GNSSTK_RETHROW
#define GNSSTK_RETHROW(exc)
Definition: Exception.hpp:369
gnsstk::Rinex3ObsStream
Definition: Rinex3ObsStream.hpp:65
example3.data
data
Definition: example3.py:22
gnsstk::Rinex3ObsData::clockOffset
double clockOffset
optional clock offset in seconds
Definition: Rinex3ObsData.hpp:112
example6.ssi
ssi
Definition: example6.py:124
gnsstk::dumpAllRinex3ObsTypes
void dumpAllRinex3ObsTypes(ostream &os)
Definition: Rinex3ObsFileLoader.cpp:764
gnsstk::StringUtils
Definition: IonexStoreStrategy.cpp:44
Rinex3ObsStream.hpp
GPSWeekSecond.hpp
gnsstk::RinexSatID::toString
std::string toString() const noexcept
Definition: RinexSatID.cpp:204
gnsstk::printTime
std::string printTime(const CommonTime &t, const std::string &fmt)
Definition: TimeString.cpp:64
gnsstk::TrackingCode
TrackingCode
Definition: TrackingCode.hpp:64
gnsstk::RinexSatID
Definition: RinexSatID.hpp:63
Exception.hpp
std
Definition: Angle.hpp:142
gnsstk::ObservationTypeIterator
EnumIterator< ObservationType, ObservationType::Unknown, ObservationType::Last > ObservationTypeIterator
Definition: ObservationType.hpp:79
gnsstk::StringUtils::leftJustify
std::string & leftJustify(std::string &s, const std::string::size_type length, const char pad=' ')
Definition: StringUtils.hpp:1582
GNSSTK_THROW
#define GNSSTK_THROW(exc)
Definition: Exception.hpp:366
Rinex3ObsFileLoader.hpp
example6.lli
lli
Definition: example6.py:123
gnsstk::vectorindex
int vectorindex(const std::vector< T > &vec, const T &value)
Definition: stl_helpers.hpp:123
TimeString.hpp
gnsstk::Rinex3ObsData::auxHeader
Rinex3ObsHeader auxHeader
auxiliary header records (epochFlag 2-5)
Definition: Rinex3ObsData.hpp:116
gnsstk::ObservationType
ObservationType
The type of observation, mostly used by ObsID.
Definition: ObservationType.hpp:55


gnsstk
Author(s):
autogenerated on Wed Oct 25 2023 02:40:41