Rinex3NavData.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 
41 
42 #include "Rinex3NavData.hpp"
43 
44 #include "CivilTime.hpp"
45 #include "GPSWeekSecond.hpp"
46 #include "GALWeekSecond.hpp"
47 #include "BDSWeekSecond.hpp"
48 #include "QZSWeekSecond.hpp"
49 #include "TimeString.hpp"
50 #include "GNSSconstants.hpp"
51 #include "StringUtils.hpp"
52 
53 namespace gnsstk
54 {
55  using namespace StringUtils;
56  using namespace std;
57 
60  : time(CommonTime::BEGINNING_OF_TIME), PRNID(-1), fitint(4),
61  xmitTime(0), weeknum(0), accuracy(0), health(0), codeflgs(0),
62  L2Pdata(0), IODC(0), IODE(0), TauN(0), GammaN(0), MFTraw(0),
63  MFtime(0), freqNum(0), ageOfInfo(0), datasources(0), IODnav(0),
64  accCode(0), IODN(0), Toc(0), af0(0), af1(0), af2(0), Tgd(0), Tgd2(0),
65  Cuc(0), Cus(0), Crc(0), Crs(0), Cic(0), Cis(0), Toe(0), M0(0), dn(0),
66  ecc(0), Ahalf(0), OMEGA0(0), i0(0), w(0), OMEGAdot(0), idot(0),
67  px(0), py(0), pz(0), vx(0), vy(0), vz(0), ax(0), ay(0), az(0)
68  {}
69 
70 
71  // Create from a RINEX version 2 RinexNavData (for backward compatibility)
73  {
74  // Epoch
75  time = rnd.time;
76  satSys = "G";
77  PRNID = rnd.PRNID;
79  xmitTime = rnd.getXmitWS().sow;
80  weeknum = rnd.getXmitWS().week;
81  accuracy = rnd.accuracy;
82  health = rnd.health;
83 
84  // flags
85  codeflgs = rnd.codeflgs;
86  L2Pdata = rnd.L2Pdata;
87  IODC = rnd.IODC;
88  IODE = rnd.IODE;
89 
90  // clock
91  Toc = rnd.getTocWS().sow;
92  af0 = rnd.af0;
93  af1 = rnd.af1;
94  af2 = rnd.af2;
95  Tgd = rnd.Tgd;
96  Tgd2 = 0.0;
97 
98  // perturbations
99  Cus = rnd.Cus;
100  Crc = rnd.Crc;
101  Crs = rnd.Crs;
102  Cic = rnd.Cic;
103  Cis = rnd.Cis;
104 
105  // Orbit parameters
106  Toe = rnd.Toe;
107  M0 = rnd.M0;
108  dn = rnd.dn;
109  ecc = rnd.ecc;
110  Ahalf = rnd.Ahalf;
111  OMEGA0 = rnd.OMEGA0;
112  i0 = rnd.i0;
113  w = rnd.w;
114  OMEGAdot = rnd.OMEGAdot;
115  idot = rnd.idot;
116  fitint = rnd.fitint;
117  }
118 
119 
120  // Deprecated
121  // This routine uses EngEphemeris, so is for GPS data only.
122  // The comments about GPS v. Galileo next to each elements are just notes
123  // from sorting out the ICDs in the RINEX 3 documentation. Please leave
124  // them there until we add a routine for handling GalRecord or similar.
126  {
127  // epoch info
128  satSys = ee.getSatSys();
129  PRNID = ee.getPRNID();
131  time = ee.getEpochTime();
132 
133  Toc = ee.getToc();
135  weeknum = ee.getFullWeek();
136 
137  accuracy = ee.getAccuracy();
138  health = ee.getHealth();
139 
140  // GPS or Galileo data
141 
142  af0 = ee.getAf0(); // GPS and Galileo only
143  af1 = ee.getAf1(); // GPS and Galileo only
144  af2 = ee.getAf2(); // GPS and Galileo only
145 
146  Crs = ee.getCrs(); // GPS and Galileo only
147  dn = ee.getDn(); // GPS and Galileo only
148  M0 = ee.getM0(); // GPS and Galileo only
149 
150  Cuc = ee.getCuc(); // GPS and Galileo only
151  ecc = ee.getEcc(); // GPS and Galileo only
152  Cus = ee.getCus(); // GPS and Galileo only
153  Ahalf = ee.getAhalf(); // GPS and Galileo only
154 
155  Toe = ee.getToe(); // GPS and Galileo only
156  Cic = ee.getCic(); // GPS and Galileo only
157  OMEGA0 = ee.getOmega0(); // GPS and Galileo only
158  Cis = ee.getCis(); // GPS and Galileo only
159 
160  i0 = ee.getI0(); // GPS and Galileo only
161  Crc = ee.getCrc(); // GPS and Galileo only
162  w = ee.getW(); // GPS and Galileo only
163  OMEGAdot = ee.getOmegaDot(); // GPS and Galileo only
164 
165  idot = ee.getIDot(); // GPS and Galileo only
166 
167  // GPS-only data
168 
169  IODE = ee.getIODE(); // GPS only
170 
171  codeflgs = ee.getCodeFlags(); // GPS only
172  L2Pdata = ee.getL2Pdata(); // GPS only
173 
174  Tgd = ee.getTgd(); // GPS only
175  IODC = ee.getIODC(); // GPS only
176 
177  fitint = ee.getFitInterval(); // GPS only
178  } // End of 'Rinex3NavData::Rinex3NavData(const EngEphemeris& ee)'
179 
180 
181  /* This function retrieves a RINEX 3 NAV record from the given
182  * FFStream.
183  * If an error is encountered in reading from the stream, the stream
184  * is returned to its original position and its fail-bit is set.
185  * @throw StringException when a StringUtils function fails.
186  * @throw FFStreamError when exceptions(failbit) is set and a read
187  * or formatting error occurs. This also resets the stream
188  * to its pre-read position.
189  */
191  {
192 
193  try
194  {
195  Rinex3NavStream& strm = dynamic_cast<Rinex3NavStream&>(ffs);
196 
197  // If the header hasn't been read, read it...
198  if (!strm.headerRead)
199  {
200  try
201  {
202  strm >> strm.header;
203  }
204  catch(std::exception& e)
205  {
206  FFStreamError fse(string("std::exception reading header ") +
207  e.what());
208  GNSSTK_THROW(fse);
209  }
210  catch(FFStreamError& fse)
211  {
212  GNSSTK_RETHROW(fse);
213  }
214  }
215 
216  // get the first line, the epoch line
217  getPRNEpoch(strm);
218 
219  // get 3 data records
220  for(int i=1; i<=3; i++) getRecord(i, strm);
221 
222  // SBAS and GLO only have 3 records
223  if (satSys == "S" || satSys == "R") return;
224 
225  // GPS GAL QZSS BDS have 7 records, get 4-7
226  if (satSys == "G" || satSys == "E" || satSys == "J" || satSys == "C" ||
227  satSys == "I")
228  {
229  for(int i=4; i<=7; i++)
230  {
231  getRecord(i, strm);
232  }
233  }
234  }
235  catch(std::exception& e)
236  {
237  FFStreamError fse(string("std::exception: ") + e.what());
238  GNSSTK_THROW(fse);
239  }
240  catch(FFStreamError& fse)
241  {
242  GNSSTK_RETHROW(fse);
243  }
244  catch(StringException& se)
245  {
247  }
248 
249  } // End of method 'Rinex3NavData::reallyGetRecord(FFStream& ffs)'
250 
251 
252  // Outputs the record to the FFStream \a s.
254  {
255  try
256  {
257  Rinex3NavStream& strm = dynamic_cast<Rinex3NavStream&>(ffs);
258 
259  putPRNEpoch(strm);
260 
261  // put 3 data records
262  for(int i=1; i<=3; i++)
263  {
264  putRecord(i, strm);
265  }
266 
267  // SBAS and GLO only have 3 records
268  if (satSys == "S" || satSys == "R")
269  {
270  return;
271  }
272 
273  // GPS QZS BDS and GAL have 7 records, put 4-7
274  if (satSys == "G" || satSys == "C" || satSys == "E" || satSys == "J")
275  {
276  for(int i=4; i<=7; i++)
277  {
278  putRecord(i, strm);
279  }
280  }
281  }
282  catch(std::exception& e)
283  {
284  FFStreamError fse(string("std::exception: ") + e.what());
285  GNSSTK_THROW(fse);
286  }
287  catch(FFStreamError& fse)
288  {
289  GNSSTK_RETHROW(fse);
290  }
291  catch(StringException& se)
292  {
294  }
295 
296  } // End of method 'Rinex3NavData::reallyPutRecord(FFStream& ffs)'
297 
298  // A debug output function.
299  // Prints the PRN id and the IODC for this record.
300  void Rinex3NavData::dump(ostream& s) const
301  {
302  s << "Rinex3NavData dump: "
303  << satSys << setfill('0') << setw(2) << PRNID << setfill(' ')
304  << printTime(time, " TOC %Y/%02m/%02d %02H:%02M:%02S")
305  << fixed << setprecision(3)
306  << " wk " << weeknum << " xmit " << xmitTime << " Toe " << Toe << endl;
307  s << " Toc " << Toc << scientific << setprecision(12)
308  << " af0 " << af0 << " af1 " << af1 << " af2 " << af2
309  << " Tgd " << Tgd << " Tgd2 " << Tgd2 << endl;
310 
311  s << " M0 " << M0 << " Ecc " << ecc << " sqrtA " << Ahalf << " OM "
312  << OMEGA0 << endl;
313  s << " i0 " << i0 << " om " << w << " dOMdt " << OMEGAdot << " didt "
314  << idot << endl;
315  s << " Cuc " << Cuc << " Cus " << Cus << " Crc " << Crc << " Crs " << Crs
316  << " Cic " << Cic << " Cis " << Cis << endl;
317 
318  if (satSys == "G" || satSys == "J")
319  {
320  // GPS QZSS
321  s << " health " << health << " acc " << accuracy << " fit " << fitint
322  << " IODE " << IODE << " IODC " << IODC
323  << " codeflags " << codeflgs << " L2P " << L2Pdata << endl;
324  }
325  //else if (satSys == "R") // GLONASS
326  else if (satSys == "E")
327  {
328  // Galileo
329  s << " IODnav " << IODnav << " datasources " << datasources << endl;
330  }
331  //else if (satSys == "C") // BeiDou
332  }
333 
334  string Rinex3NavData::dumpString(void) const
335  {
336  ostringstream s;
337  s << "RND " << satSys
338  << setfill('0') << setw(2) << PRNID << setfill(' ');
339  if (satSys == "G" || satSys == "J")
340  {
341  // GPS or QZSS
342  s << " TOE: " << setw(4) << weeknum
343  << " " << fixed << setw(10) << setprecision(3) << Toe.val
344  << " TOC: " << printTime(time,"%4Y %02m %02d %02H %02M %06.3f %P")
345  << " xmitTime: " << setw(6) << xmitTime
346  << " IODE/C: " << int(IODE) << "/" << int(IODC)
347  << " hlth: " << health
348  << " cflgs: " << codeflgs << " L2P: " << L2Pdata
349  << " fit: " << fitint.val;
350  }
351  else if (satSys == "R")
352  {
353  // GLONASS
354  s << " freq: " << setw(2) << freqNum
355  << " hlth: " << setw(2) << health
356  << " " << printTime(time,"%4Y %02m %02d %02H %02M %06.3f")
357  << " MFtime: " << setw(6) << MFtime
358  << " TauN: " << scientific << setw(19) << setprecision(12)
359  << TauN.val
360  << " GammaN: " << setw(19) << GammaN.val
361  << " AOI: " << fixed << setprecision(2) << setw(4) << ageOfInfo.val;
362  }
363  else if (satSys == "S")
364  {
365  // Geosync (SBAS)
366  s << " URAm: " << setw(2) << freqNum
367  << " hlth: " << setw(2) << health
368  << " " << printTime(time,"%4Y %02m %02d %02H %02M %06.3f")
369  << " MFtime: " << setw(6) << MFtime
370  << " aGf0: " << scientific << setw(19) << setprecision(12)
371  << TauN.val
372  << " aGf1: " << setw(19) << GammaN.val
373  << " IODN " << fixed << setprecision(2) << setw(4) << ageOfInfo.val;
374  }
375  else if (satSys == "E")
376  {
377  // Galileo
378  s << " TOE: " << setw(4) << weeknum
379  << " " << fixed << setw(10) << setprecision(3) << Toe.val
380  << " TOC: " << printTime(time,"%4Y %02m %02d %02H %02M %06.3f %P")
381  << " xmitTime: " << setw(6) << xmitTime
382  << " IODnav: " << int(IODnav) << " hlth: " << health
383  << " datasources " << datasources;
384  }
385  else if (satSys == "C")
386  {
387  // BeiDou
388  s << " TOE: " << setw(4) << weeknum
389  << " " << fixed << setw(10) << setprecision(3) << Toe.val
390  << " TOC: " << printTime(time,"%4Y %02m %02d %02H %02M %06.3f %P")
391  << " xmitTime: " << setw(6) << xmitTime
392  << " IODE/C: " << int(IODE) << "/" << int(IODC);
393  }
394  else
395  {
396  s << " (unknown system: " << satSys << ")";
397  }
398 
399  return s.str();
400  } // End of method 'Rinex3NavData::asString
401 
402  // Deprecated; use GPSEphemeris.
403  // Converts this Rinex3NavData to an EngEphemeris object.
404  Rinex3NavData::operator EngEphemeris() const noexcept
405  {
406  EngEphemeris ee;
407 
408  // There's no TLM word in Rinex3NavData, so it's set to 0.
409  // Likewise, there's no AS alert or tracker.
410  // Also, in RINEX, the accuracy is in meters, and setSF1 expects
411  // the accuracy flag. We'll give it zero and pass the accuracy
412  // separately via the setAccuracy() method.
413 
414  ee.tlm_message[0] = 0;
415  ee.tlm_message[1] = 0;
416  ee.tlm_message[2] = 0;
417  ee.HOWtime[0] = xmitTime + 6; // GPS standard specifies
418  ee.HOWtime[1] = ee.HOWtime[0] + 6; // how the transmit time
419  ee.HOWtime[2] = ee.HOWtime[1] + 6; // relates to HOWtime.
420  ee.ASalert[0] = 1; //AS and alert flags set to 1 (default)
421  ee.ASalert[1] = 1;
422  ee.ASalert[2] = 1;
423 
424  ee.weeknum = weeknum;
425  ee.codeflags = codeflgs;
426  ee.health = health;
427  ee.IODC = short(IODC);
428  ee.L2Pdata = L2Pdata;
429  ee.Tgd = Tgd;
430  ee.tracker = 0;
431  ee.PRNID = PRNID;
432  ee.satSys = satSys;
433  bool healthy = false;
434  if (health == 0) healthy = true;
435  short accFlag = 0; //will be set later.
436  //BrcClockCorrection takes a flag, while EngEphemeris takes a double.
437  double toc = Toc;
438 
439  double timeDiff =toc - ee.HOWtime[0];
440  short epochWeek = ee.weeknum;
441  if (timeDiff < -HALFWEEK) epochWeek++;
442  else if (timeDiff > HALFWEEK) epochWeek--;
443 
444  CommonTime tocCT = GPSWeekSecond(epochWeek, Toc, TimeSystem::GPS);
445 
446  // The observation ID has a type of navigation, but the
447  // carrier and code types are undefined. They could be
448  // L1/L2 C/A, P, Y,.....
450  ee.bcClock.loadData( satSys, obsID, PRNID, tocCT,
451  accFlag, healthy, af0, af1, af2);
452 
453  ee.IODE = short(IODE);
454  ee.fitint = (fitint > 4) ? 1 : 0;
455  //double toe = Toe; //?????
456 
457  //Needed for modernized nav quatities
458  double A = Ahalf * Ahalf;
459  double dndot = 0.0;
460  double Adot = 0.0;
461 
462  short fitHours = getLegacyFitInterval(ee.IODC, ee.fitint);
463  long beginFitSOW = Toe - (fitHours/2)*3600.0;
464  long endFitSOW = Toe + (fitHours/2)*3600.0;
465  short beginFitWk = ee.weeknum;
466  short endFitWk = ee.weeknum;
467 
468  if (beginFitSOW < 0)
469  {
470  beginFitSOW += FULLWEEK;
471  beginFitWk--;
472  }
473  CommonTime beginFit = GPSWeekSecond(beginFitWk, beginFitSOW,
475  if (endFitSOW >= FULLWEEK)
476  {
477  endFitSOW += FULLWEEK;
478  endFitWk++;
479  }
480 
481  CommonTime endFit = GPSWeekSecond(endFitWk, endFitSOW, TimeSystem::GPS);
482  CommonTime toeCT = GPSWeekSecond(epochWeek, Toe, TimeSystem::GPS);
483 
484  ee.orbit.loadData( satSys, obsID, PRNID, beginFit, endFit, toeCT,
485  accFlag, healthy, Cuc, Cus, Crc, Crs, Cic, Cis,
486  M0, dn, dndot, ecc, A, Ahalf, Adot, OMEGA0, i0,
487  w, OMEGAdot, idot);
488 
489  ee.haveSubframe[0] = true; // need to be true to perform certain EngEphemeris functions
490  ee.haveSubframe[1] = true; // examples: ee.dump(), ee.setAccuracy()
491  ee.haveSubframe[2] = true;
492 
493  ee.setAccuracy(accuracy);
494 
495  return ee;
496 
497  } // End of 'Rinex3NavData::operator EngEphemeris()'
498 
499 
500  // Converts the (non-CommonTime) data to an easy list
501  // for comparison operators.
502  list<double> Rinex3NavData::toList() const
503  {
504 
505  list<double> l;
506 
507  l.push_back(PRNID);
508  l.push_back(xmitTime);
509  l.push_back(weeknum);
510  l.push_back(codeflgs);
511  l.push_back(accuracy.val);
512  l.push_back(health);
513  l.push_back(L2Pdata);
514  l.push_back(IODC.val);
515  l.push_back(IODE.val);
516  l.push_back(Toe.val);
517  l.push_back(af0.val);
518  l.push_back(af1.val);
519  l.push_back(af2.val);
520  l.push_back(Tgd.val);
521  l.push_back(Cuc.val);
522  l.push_back(Cus.val);
523  l.push_back(Crc.val);
524  l.push_back(Crs.val);
525  l.push_back(Cic.val);
526  l.push_back(Cis.val);
527  l.push_back(Toc);
528  l.push_back(M0.val);
529  l.push_back(dn.val);
530  l.push_back(ecc.val);
531  l.push_back(Ahalf.val);
532  l.push_back(OMEGA0.val);
533  l.push_back(i0.val);
534  l.push_back(w.val);
535  l.push_back(OMEGAdot.val);
536  l.push_back(idot.val);
537  l.push_back(fitint.val);
538 
539  return l;
540 
541  } // End of method 'Rinex3NavData::toList()'
542 
543 
544  /* Generates the PRN/epoch line and outputs it to strm
545  * @param strm RINEX Nav stream
546  */
548  {
549  string line;
550  CivilTime civtime(time);
551 
552  if (strm.header.version >= 3)
553  {
554  // version 3
555  strm << sat.toString() << ' '
556  << printTime(civtime, "%4Y %02m %02d %02H %02M %02S");
557  }
558  else
559  {
560  // version 2
561  strm << right << setw(2) << PRNID << ' '
562  << printTime(civtime, "%02y %2m %2d %2H %2M %4.1f");
563  }
564 
565  if (satSys == "R" || satSys == "S")
566  {
567  strm << TauN << GammaN << RNDouble(MFtime);
568  }
569  else if (satSys == "G" || satSys == "E" || satSys == "J" || satSys == "C")
570  {
571  strm << af0 << af1 << af2;
572  }
573 
574  strm << endl;
575  strm.lineNumber++;
576  } // End of 'Rinex3NavData::putPRNEpoch(Rinex3NavStream& strm)'
577 
578 
579  // Construct and write the nth record after the epoch record
580  // @param int n Record number (1-7), for nth record
581  // after the epoch line.
582  // @param Rinex3NavStream strm Stream to read from.
583  void Rinex3NavData::putRecord(const int& nline, Rinex3NavStream& strm) const
584  {
585 
586  if (nline < 1 || nline > 7)
587  {
588  FFStreamError fse(string("Invalid line number ") + asString(nline));
589  GNSSTK_THROW(fse);
590  }
591 
592  try
593  {
594  if (strm.header.version < 3)
595  {
596  strm << " ";
597  }
598  else
599  {
600  strm << " ";
601  }
602 
603 
604  // Internally (Rinex3NavData), weeknum=week of HOW
605  // In RINEX 3 *files*, weeknum is the week of TOE.
606  RNDouble wk(weeknum);
607  long xmit = xmitTime;
608  if (xmit - Toe > HALFWEEK)
609  {
610  xmit -= FULLWEEK;
611  wk++;
612  }
613  else if (xmit - Toe < -(HALFWEEK))
614  {
615  xmit += FULLWEEK;
616  wk--;
617  }
618 
619  if (nline == 1)
620  {
621  if (satSys == "R" || satSys == "S")
622  {
623  // GLO and GEO
624  strm << px << vx << ax << RNDouble(health);
625  }
626  else if (satSys == "G" || satSys == "C" || satSys == "J")
627  {
628  // GPS,BDS,QZS
629  strm << IODE << Crs << dn << M0;
630  }
631  else if (satSys == "E")
632  {
633  // GAL
634  strm << IODnav << Crs << dn << M0;
635  }
636  }
637  else if (nline == 2)
638  {
639  if (satSys == "R" || satSys == "S")
640  {
641  // GLO and GEO
642  strm << py << vy << ay;
643  if (satSys == "R")
644  strm << RNDouble(freqNum);
645  else
646  strm << accCode;
647  }
648  else
649  {
650  // GPS,GAL,BDS,QZS
651  strm << Cuc << ecc << Cus << Ahalf;
652  }
653  }
654  else if (nline == 3)
655  {
656  if (satSys == "R" || satSys == "S")
657  {
658  // GLO GEO
659  strm << pz << vz << az;
660  if (satSys == "R")
661  strm << ageOfInfo;
662  else // GEO
663  strm << IODN;
664  }
665  else
666  {
667  // GPS,GAL,BDS,QZS
668  strm << Toe << Cic << OMEGA0 << Cis;
669  }
670  }
671 
672  // SBAS and GLO end here
673 
674  else if (nline == 4)
675  {
676  // GPS,GAL,BDS,QZS
677  strm << i0 << Crc << w << OMEGAdot;
678  }
679 
680  else if (nline == 5)
681  {
682  if (satSys == "G" || satSys == "J")
683  {
684  // GPS QZS
685  strm << idot << RNDouble(codeflgs) << wk << RNDouble(L2Pdata);
686  }
687  else if (satSys == "E")
688  {
689  // GAL
690  strm << idot << RNDouble(datasources) << wk << RNDouble(0);
691  }
692  else if (satSys == "C")
693  {
694  // BDS
695  strm << idot << RNDouble(0) << wk << RNDouble(0);
696  }
697  }
698 
699  else if (nline == 6)
700  {
701  strm << accuracy << RNDouble(health);
702 
703  if (satSys == "G" || satSys == "J")
704  {
705  // GPS, QZS
706  strm << Tgd << IODC;
707  }
708  else if (satSys == "E" || satSys == "C")
709  {
710  // GAL, BDS
711  strm << Tgd << Tgd2;
712  }
713  }
714 
715  else if (nline == 7)
716  {
717  strm << RNDouble(xmit);
718  if (satSys == "G" || satSys == "J")
719  {
720  strm << fitint;
721  }
722  else if (satSys == "E")
723  {
724  ;
725  }
726  else if (satSys == "C")
727  {
728  strm << IODC;
729  }
730  }
731 
732  strm << endl;
733  strm.lineNumber++;
734  }
735  catch (std::exception &e)
736  {
737  FFStreamError err("std::exception: " + string(e.what()));
738  GNSSTK_THROW(err);
739  }
740 
741  } // End of method 'Rinex3NavData::putRecord(const int& nline,...'
742 
743 
745  {
746  try
747  {
748  int i;
749  short yr,mo,day,hr,min;
750  double dsec;
751 
752  string line;
753  while(line.empty()) // ignore blank lines in place of epoch lines
754  strm.formattedGetLine(line, true);
755 
756  if (strm.header.version >= 3)
757  {
758  // check for spaces in the right spots...
759  if (line[3] != ' ')
760  GNSSTK_THROW(FFStreamError("Badly formatted epoch line"));
761  for(i = 8; i <= 20; i += 3)
762  {
763  if (line[i] != ' ')
764  {
765  GNSSTK_THROW(FFStreamError("Badly formatted epoch line"));
766  }
767  }
768 
769  satSys = line.substr(0,1);
770  PRNID = asInt(line.substr(1,2));
771  sat.fromString(line.substr(0,3));
772 
773  yr = asInt(line.substr( 4,4));
774  mo = asInt(line.substr( 9,2));
775  day = asInt(line.substr(12,2));
776  hr = asInt(line.substr(15,2));
777  min = asInt(line.substr(18,2));
778  dsec = asDouble(line.substr(21,2));
779  }
780  else
781  {
782  // RINEX 2
783  for(i=2; i <= 17; i+=3)
784  {
785  if (line[i] != ' ')
786  {
787  GNSSTK_THROW(FFStreamError("Badly formatted epoch line"));
788  }
789  }
790 
791  satSys = string(1,strm.header.fileSys[0]);
792  PRNID = asInt(line.substr(0,2));
793  sat.fromString(satSys + line.substr(0,2));
794 
795  yr = asInt(line.substr( 2,3));
796  if (yr < 80)
797  yr += 100; // rollover is at 1980
798  yr += 1900;
799  mo = asInt(line.substr( 5,3));
800  day = asInt(line.substr( 8,3));
801  hr = asInt(line.substr(11,3));
802  min = asInt(line.substr(14,3));
803  dsec = asDouble(line.substr(17,5));
804  }
805 
806  // Fix RINEX epochs of the form 'yy mm dd hr 59 60.0'
807  short ds = 0;
808  if (dsec >= 60.)
809  {
810  ds = dsec;
811  dsec = 0;
812  }
813  time = CivilTime(yr,mo,day,hr,min,dsec).convertToCommonTime();
814  if (ds != 0)
815  time += ds;
816 
817  // specify the time system based on satellite system
825 
826  // TOC is the clock time
827  GPSWeekSecond gws(time); // sow is system-independent
828  Toc = gws.sow;
829 
830  if (strm.header.version < 3)
831  {
832  // Rinex 2.*
833  if (satSys == "G")
834  {
835  af0 = line.substr(22,19);
836  af1 = line.substr(41,19);
837  af2 = line.substr(60,19);
838  }
839  else if (satSys == "R" || satSys == "S")
840  {
841  TauN = line.substr(22,19);
842  GammaN = line.substr(41,19);
843  MFtime = RNDouble(line.substr(60,19));
844  if (satSys == "R")
845  {
846  // make MFtime consistent with R3.02
847  MFtime += int(Toc/86400) * 86400;
848  }
849  }
850  }
851  else if (satSys == "G" || satSys == "E" || satSys == "C" ||
852  satSys == "J")
853  {
854  af0 = line.substr(23,19);
855  af1 = line.substr(42,19);
856  af2 = line.substr(61,19);
857  }
858  else if (satSys == "R" || satSys == "S")
859  {
860  TauN = line.substr(23,19);
861  GammaN = line.substr(42,19);
862  MFtime = RNDouble(line.substr(61,19));
863  }
864  }
865  catch (std::exception &e)
866  {
867  FFStreamError err("std::exception: " + string(e.what()));
868  GNSSTK_THROW(err);
869  }
870  }
871 
872 
873  void Rinex3NavData::getRecord(const int& nline, Rinex3NavStream& strm)
874  {
875  if (nline < 1 || nline > 7)
876  {
877  FFStreamError fse(string("Invalid line number ") + asString(nline));
878  GNSSTK_THROW(fse);
879  }
880 
881  try
882  {
883  int n(strm.header.version < 3 ? 3 : 4);
884  string line;
885  strm.formattedGetLine(line);
886 
887  if (nline == 1)
888  {
889  if (satSys == "G" || satSys == "J" || satSys == "C")
890  {
891  IODE = line.substr(n,19); n+=19;
892  Crs = line.substr(n,19); n+=19;
893  dn = line.substr(n,19); n+=19;
894  M0 = line.substr(n,19);
895  }
896  else if (satSys == "E")
897  {
898  IODnav = line.substr(n,19); n+=19;
899  Crs = line.substr(n,19); n+=19;
900  dn = line.substr(n,19); n+=19;
901  M0 = line.substr(n,19);
902  }
903  else if (satSys == "R" || satSys == "S")
904  {
905  px = line.substr(n,19); n+=19;
906  vx = line.substr(n,19); n+=19;
907  ax = line.substr(n,19); n+=19;
908  health = RNDouble(line.substr(n,19));
909  }
910  }
911 
912  else if (nline == 2)
913  {
914  if (satSys == "G" || satSys == "E" || satSys == "J" ||
915  satSys == "C")
916  {
917  Cuc = line.substr(n,19); n+=19;
918  ecc = line.substr(n,19); n+=19;
919  Cus = line.substr(n,19); n+=19;
920  Ahalf = line.substr(n,19);
921  }
922  else if (satSys == "R" || satSys == "S")
923  {
924  py = line.substr(n,19); n+=19;
925  vy = line.substr(n,19); n+=19;
926  ay = line.substr(n,19); n+=19;
927  if (satSys == "R")
928  {
929  freqNum = RNDouble(line.substr(n,19));
930  }
931  else // GEO
932  {
933  accCode = line.substr(n,19);
934  }
935  }
936  }
937 
938  else if (nline == 3)
939  {
940  if (satSys == "G" || satSys == "E" || satSys == "J" ||
941  satSys == "C")
942  {
943  Toe = line.substr(n,19); n+=19;
944  Cic = line.substr(n,19); n+=19;
945  OMEGA0 = line.substr(n,19); n+=19;
946  Cis = line.substr(n,19);
947  }
948  else if (satSys == "R" || satSys == "S")
949  {
950  pz = line.substr(n,19); n+=19;
951  vz = line.substr(n,19); n+=19;
952  az = line.substr(n,19); n+=19;
953  if (satSys == "R")
954  {
955  ageOfInfo = line.substr(n,19);
956  }
957  else // GEO
958  {
959  IODN = line.substr(n,19);
960  }
961  }
962  }
963 
964  else if (nline == 4)
965  {
966  i0 = line.substr(n,19); n+=19;
967  Crc = line.substr(n,19); n+=19;
968  w = line.substr(n,19); n+=19;
969  OMEGAdot = line.substr(n,19);
970  }
971 
972  else if (nline == 5)
973  {
974  if (satSys == "G" || satSys == "J" || satSys == "C")
975  {
976  idot = line.substr(n,19); n+=19;
977  codeflgs = RNDouble(line.substr(n,19)); n+=19;
978  weeknum = RNDouble(line.substr(n,19)); n+=19;
979  L2Pdata = RNDouble(line.substr(n,19));
980  }
981  else if (satSys == "E")
982  {
983  idot = line.substr(n,19); n+=19;
984  datasources =RNDouble(line.substr(n,19)); n+=19;
985  weeknum =RNDouble(line.substr(n,19)); n+=19;
986  }
987  }
988 
989  else if (nline == 6)
990  {
991  Tgd2 = 0.0;
992  if (satSys == "G" || satSys == "J")
993  {
994  accuracy = line.substr(n,19); n+=19;
995  health = RNDouble(line.substr(n,19)); n+=19;
996  Tgd = line.substr(n,19); n+=19;
997  IODC = line.substr(n,19);
998  }
999  else if (satSys == "E")
1000  {
1001  accuracy = line.substr(n,19); n+=19;
1002  health = RNDouble(line.substr(n,19)); n+=19;
1003  Tgd = line.substr(n,19); n+=19;
1004  Tgd2 = line.substr(n,19);
1005  }
1006  else if (satSys == "C")
1007  {
1008  accuracy = line.substr(n,19); n+=19;
1009  health = RNDouble(line.substr(n,19)); n+=19;
1010  Tgd = line.substr(n,19); n+=19;
1011  Tgd2 = line.substr(n,19);
1012  }
1013  }
1014 
1015  else if (nline == 7)
1016  {
1017  xmitTime = RNDouble(line.substr(n,19)); n+=19;
1018  if (satSys == "C")
1019  {
1020  IODC = line.substr(n,19); n+=19;
1021  }
1022  else
1023  {
1024  fitint = line.substr(n,19); n+=19;
1025  }
1026 
1027  // Some RINEX files have xmitTime < 0.
1028  while(xmitTime < 0)
1029  {
1030  xmitTime += (long)FULLWEEK;
1031  }
1032 
1033  // In RINEX *files*, weeknum is the week of TOE.
1034  // Internally (Rinex3NavData), weeknum is week of transmission
1035  if (xmitTime - Toe > HALFWEEK)
1036  weeknum--;
1037  else if (xmitTime - Toe < -HALFWEEK)
1038  weeknum++;
1039  }
1040  }
1041  catch (std::exception &e)
1042  {
1043  FFStreamError err("std::exception: " + string(e.what()));
1044  GNSSTK_THROW(err);
1045  }
1046 
1047  } // end getRecord()
1048 
1049 
1050 } // End of namespace gnsstk
gnsstk::RNDouble
Definition: RNDouble.hpp:50
gnsstk::Rinex3NavData::fitint
RNDouble fitint
Fit interval.
Definition: Rinex3NavData.hpp:197
gnsstk::EngEphemeris::getTgd
double getTgd() const
Definition: EngEphemeris.cpp:795
gnsstk::RinexNavData::Toe
RNDouble Toe
Ephemeris epoch (sec of week).
Definition: RinexNavData.hpp:237
gnsstk::StringUtils::asInt
long asInt(const std::string &s)
Definition: StringUtils.hpp:713
gnsstk::EngEphemeris::getHealth
short getHealth() const
Definition: EngEphemeris.cpp:705
se
double se
obliquity cos, T*cos, sin coefficients
Definition: IERS2003NutationData.hpp:48
gnsstk::Rinex3NavData::Ahalf
RNDouble Ahalf
SQRT of semi-major axis (m**1/2)
Definition: Rinex3NavData.hpp:191
gnsstk::RinexNavData::Crc
RNDouble Crc
Cosine radius (m).
Definition: RinexNavData.hpp:228
gnsstk::Rinex3NavData::vz
RNDouble vz
SV velocity.
Definition: Rinex3NavData.hpp:204
gnsstk::Rinex3NavData::py
RNDouble py
Definition: Rinex3NavData.hpp:203
gnsstk::RinexNavData::Cic
RNDouble Cic
Cosine inclination (rad).
Definition: RinexNavData.hpp:230
gnsstk::Rinex3NavData::Toc
double Toc
Time of clock (sec of week)
Definition: Rinex3NavData.hpp:167
gnsstk::HALFWEEK
const long HALFWEEK
Seconds per half week.
Definition: TimeConstants.hpp:58
gnsstk::EngEphemeris::fitint
short fitint
Definition: EngEphemeris.hpp:648
example6.day
day
Definition: example6.py:66
gnsstk::Rinex3NavHeader::version
double version
RINEX Version.
Definition: Rinex3NavHeader.hpp:178
gnsstk::Rinex3NavData::Cuc
RNDouble Cuc
Cosine latitude (rad)
Definition: Rinex3NavData.hpp:177
gnsstk::Rinex3NavData::Tgd2
RNDouble Tgd2
Group delay differential (sec) (BDS:B2/B3 GAL:E5b/E1)
Definition: Rinex3NavData.hpp:172
gnsstk::RinexSatID::fromString
void fromString(const std::string &s)
Definition: RinexSatID.cpp:122
gnsstk::Rinex3NavStream
Definition: Rinex3NavStream.hpp:62
gnsstk::RinexNavData::L2Pdata
short L2Pdata
L2 P data flag.
Definition: RinexNavData.hpp:209
gnsstk::EngEphemeris::getFitInterval
short getFitInterval() const
Definition: EngEphemeris.cpp:428
gnsstk::RinexNavData::Crs
RNDouble Crs
Sine radius (m).
Definition: RinexNavData.hpp:229
gnsstk::FFStream
Definition: FFStream.hpp:119
gnsstk::EngEphemeris::setAccuracy
void setAccuracy(double acc)
Definition: EngEphemeris.cpp:417
gnsstk::Rinex3NavData::time
CommonTime time
Time according to the sat/epoch record (TOC)
Definition: Rinex3NavData.hpp:122
gnsstk::BEGINNING_OF_TIME
const Epoch BEGINNING_OF_TIME(CommonTime::BEGINNING_OF_TIME)
Earliest representable Epoch.
const
#define const
Definition: getopt.c:43
StringUtils.hpp
gnsstk::Rinex3NavData::Cic
RNDouble Cic
Cosine inclination (rad)
Definition: Rinex3NavData.hpp:181
gnsstk::RinexNavData::accuracy
RNDouble accuracy
SV accuracy (m).
Definition: RinexNavData.hpp:207
gnsstk::Rinex3NavData::IODN
RNDouble IODN
Definition: Rinex3NavData.hpp:161
gnsstk::EngEphemeris::satSys
std::string satSys
Definition: EngEphemeris.hpp:632
gnsstk::Rinex3NavData::satSys
std::string satSys
Satellite system of Epoch: G,R,E,S,C.
Definition: Rinex3NavData.hpp:123
gnsstk::Rinex3NavData::ax
RNDouble ax
Definition: Rinex3NavData.hpp:205
gnsstk::EngEphemeris::getEcc
double getEcc() const
Definition: EngEphemeris.cpp:895
gnsstk::FFTextStream::formattedGetLine
void formattedGetLine(std::string &line, const bool expectEOF=false)
Definition: FFTextStream.cpp:149
gnsstk::FULLWEEK
const long FULLWEEK
Seconds per whole week.
Definition: TimeConstants.hpp:60
gnsstk::Rinex3NavData::Toe
RNDouble Toe
Ephemeris epoch (sec of week)
Definition: Rinex3NavData.hpp:187
gnsstk::RinexNavData::codeflgs
short codeflgs
L2 codes.
Definition: RinexNavData.hpp:206
gnsstk::Rinex3NavData::ecc
RNDouble ecc
Eccentricity.
Definition: Rinex3NavData.hpp:190
gnsstk::Rinex3NavData::IODC
RNDouble IODC
Index of data-clock.
Definition: Rinex3NavData.hpp:138
gnsstk::Rinex3NavData::af2
RNDouble af2
SV clock drift rate (sec/sec**2)
Definition: Rinex3NavData.hpp:170
gnsstk::EngEphemeris::getFullWeek
short getFullWeek() const
Definition: EngEphemeris.cpp:665
gnsstk::RinexNavData::w
RNDouble w
Argument of perigee (rad).
Definition: RinexNavData.hpp:244
gnsstk::Rinex3NavStream::header
Rinex3NavHeader header
RINEX NAV header for this file.
Definition: Rinex3NavStream.hpp:80
gnsstk::FFTextStream::lineNumber
unsigned int lineNumber
Definition: FFTextStream.hpp:98
gnsstk::Rinex3NavData::health
short health
SV health.
Definition: Rinex3NavData.hpp:131
gnsstk::EngEphemeris::getEpochTime
CommonTime getEpochTime() const
Definition: EngEphemeris.cpp:588
gnsstk::Rinex3NavData::i0
RNDouble i0
Inclination (rad)
Definition: Rinex3NavData.hpp:193
gnsstk::TimeSystem::Any
@ Any
wildcard; allows comparison with any other type
gnsstk::Rinex3NavData::OMEGA0
RNDouble OMEGA0
Rt ascension of ascending node (rad)
Definition: Rinex3NavData.hpp:192
gnsstk::RinexNavData::OMEGA0
RNDouble OMEGA0
Rt ascension of ascending node (rad).
Definition: RinexNavData.hpp:242
gnsstk::StringUtils::asString
std::string asString(IonexStoreStrategy e)
Convert a IonexStoreStrategy to a whitespace-free string name.
Definition: IonexStoreStrategy.cpp:46
gnsstk::Rinex3NavData::putPRNEpoch
void putPRNEpoch(Rinex3NavStream &strm) const
Definition: Rinex3NavData.cpp:547
gnsstk::EngEphemeris::getIDot
double getIDot() const
Definition: EngEphemeris.cpp:965
gnsstk::CommonTime::setTimeSystem
CommonTime & setTimeSystem(TimeSystem timeSystem)
Definition: CommonTime.hpp:195
gnsstk::Rinex3NavData::Crs
RNDouble Crs
Sine radius (m)
Definition: Rinex3NavData.hpp:180
gnsstk::Rinex3NavData::toList
std::list< double > toList() const
Definition: Rinex3NavData.cpp:502
gnsstk::EngEphemeris::getOmega0
double getOmega0() const
Definition: EngEphemeris.cpp:925
gnsstk::RinexNavData::OMEGAdot
RNDouble OMEGAdot
Rate of Rt ascension (rad/sec).
Definition: RinexNavData.hpp:245
gnsstk::RinexNavData::getXmitWS
GPSWeekSecond getXmitWS() const
Definition: RinexNavData.cpp:411
gnsstk::EngEphemeris::getCrc
double getCrc() const
Definition: EngEphemeris.cpp:835
gnsstk::RinexNavData::M0
RNDouble M0
Mean anomaly (rad).
Definition: RinexNavData.hpp:238
gnsstk::EngEphemeris::getAhalf
double getAhalf() const
Definition: EngEphemeris.cpp:905
GNSSconstants.hpp
gnsstk::Rinex3NavData::OMEGAdot
RNDouble OMEGAdot
Rate of Rt ascension (rad/sec)
Definition: Rinex3NavData.hpp:195
gnsstk::EngEphemeris::getHOWTime
double getHOWTime(short subframe) const
Definition: EngEphemeris.cpp:639
gnsstk::RinexNavData::Cus
RNDouble Cus
Sine latitude (rad).
Definition: RinexNavData.hpp:227
gnsstk::EngEphemeris::getAf1
double getAf1() const
Definition: EngEphemeris.cpp:775
gnsstk::Rinex3NavData::IODE
RNDouble IODE
Index of data-eph.
Definition: Rinex3NavData.hpp:139
gnsstk::Rinex3NavData::dn
RNDouble dn
Correction to mean motion (rad/sec)
Definition: Rinex3NavData.hpp:189
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::RinexNavData
Definition: RinexNavData.hpp:67
gnsstk::EngEphemeris::HOWtime
long HOWtime[3]
Definition: EngEphemeris.hpp:635
gnsstk::EngEphemeris::IODE
short IODE
Definition: EngEphemeris.hpp:646
gnsstk::EngEphemeris::PRNID
short PRNID
Definition: EngEphemeris.hpp:633
gnsstk::GPSWeekSecond
Definition: GPSWeekSecond.hpp:56
Rinex3NavData.hpp
gnsstk::Rinex3NavData::Crc
RNDouble Crc
Cosine radius (m)
Definition: Rinex3NavData.hpp:179
gnsstk::Rinex3NavStream::headerRead
bool headerRead
Flag showing whether or not the header has been read.
Definition: Rinex3NavStream.hpp:83
gnsstk::EngEphemeris::Tgd
double Tgd
Definition: EngEphemeris.hpp:649
gnsstk::RinexNavData::ecc
RNDouble ecc
Eccentricity.
Definition: RinexNavData.hpp:240
gnsstk::EngEphemeris::IODC
short IODC
Definition: EngEphemeris.hpp:645
gnsstk::Rinex3NavData::ageOfInfo
RNDouble ageOfInfo
Age of oper. information (days)
Definition: Rinex3NavData.hpp:149
gnsstk::EngEphemeris::getCis
double getCis() const
Definition: EngEphemeris.cpp:825
gnsstk::ObservationType::NavMsg
@ NavMsg
Navigation Message data.
gnsstk::Rinex3NavData::putRecord
void putRecord(const int &n, Rinex3NavStream &strm) const
Definition: Rinex3NavData.cpp:583
gnsstk::SatelliteSystem::GPS
@ GPS
gnsstk::EngEphemeris::bcClock
BrcClockCorrection bcClock
Clock information.
Definition: EngEphemeris.hpp:663
gnsstk::EngEphemeris
Definition: EngEphemeris.hpp:86
gnsstk::Rinex3NavData::PRNID
short PRNID
SV PRN ID.
Definition: Rinex3NavData.hpp:124
gnsstk::RinexNavData::Tgd
RNDouble Tgd
Group delay differential (sec).
Definition: RinexNavData.hpp:220
gnsstk::Rinex3NavData::datasources
short datasources
Data sources.
Definition: Rinex3NavData.hpp:154
gnsstk::EngEphemeris::getL2Pdata
short getL2Pdata() const
Definition: EngEphemeris.cpp:715
gnsstk::RinexNavData::time
CommonTime time
Clock reference time (toc).
Definition: RinexNavData.hpp:198
gnsstk::Rinex3NavData::vx
RNDouble vx
Definition: Rinex3NavData.hpp:204
gnsstk::CivilTime::convertToCommonTime
virtual CommonTime convertToCommonTime() const
Definition: CivilTime.cpp:75
gnsstk::RinexNavData::health
short health
SV health.
Definition: RinexNavData.hpp:208
gnsstk::RinexNavData::IODC
RNDouble IODC
Index of data-clock.
Definition: RinexNavData.hpp:210
gnsstk::EngEphemeris::getAf2
double getAf2() const
Definition: EngEphemeris.cpp:785
gnsstk::Rinex3NavData::dump
virtual void dump(std::ostream &s) const
Definition: Rinex3NavData.cpp:300
gnsstk::Rinex3NavData::codeflgs
short codeflgs
L2 codes.
Definition: Rinex3NavData.hpp:136
gnsstk::EngEphemeris::getDn
double getDn() const
Definition: EngEphemeris.cpp:885
gnsstk::TimeSystem::QZS
@ QZS
QZSS system Time.
gnsstk::EngEphemeris::getIODC
short getIODC() const
Definition: EngEphemeris.cpp:725
gnsstk::EngEphemeris::ASalert
short ASalert[3]
Definition: EngEphemeris.hpp:636
gnsstk::Rinex3NavData::freqNum
short freqNum
Frequency number (-7..+12)
Definition: Rinex3NavData.hpp:148
gnsstk::Rinex3NavData::getRecord
void getRecord(const int &n, Rinex3NavStream &strm)
Definition: Rinex3NavData.cpp:873
gnsstk::TimeSystem::GAL
@ GAL
Galileo system time.
example4.time
time
Definition: example4.py:103
gnsstk::RinexNavData::getTocWS
GPSWeekSecond getTocWS() const
Definition: RinexNavData.hpp:123
gnsstk::ObsID
Definition: ObsID.hpp:82
gnsstk::Rinex3NavData::px
RNDouble px
Definition: Rinex3NavData.hpp:203
example4.err
err
Definition: example4.py:126
gnsstk::Rinex3NavData::MFtime
long MFtime
Message frame time (sec of UTC week) as long.
Definition: Rinex3NavData.hpp:147
gnsstk::Rinex3NavData::af1
RNDouble af1
SV clock drift (sec/sec)
Definition: Rinex3NavData.hpp:169
gnsstk::EngEphemeris::getToc
double getToc() const
Definition: EngEphemeris.cpp:755
gnsstk::CommonTime
Definition: CommonTime.hpp:84
gnsstk::Rinex3NavData::L2Pdata
short L2Pdata
L2 P data flag.
Definition: Rinex3NavData.hpp:137
gnsstk::Rinex3NavData::Tgd
RNDouble Tgd
Group delay diff. (sec) (GPS, BDS:B1/B3 GAL:E5a/E1)
Definition: Rinex3NavData.hpp:171
gnsstk::WeekSecond::sow
double sow
Definition: WeekSecond.hpp:155
gnsstk::RinexNavData::PRNID
short PRNID
SV PRN ID.
Definition: RinexNavData.hpp:199
gnsstk::min
T min(const SparseMatrix< T > &SM)
Maximum element - return 0 if empty.
Definition: SparseMatrix.hpp:858
gnsstk::RinexNavData::dn
RNDouble dn
Correction to mean motion (rad/sec).
Definition: RinexNavData.hpp:239
gnsstk::getLegacyFitInterval
short getLegacyFitInterval(const short iodc, const short fiti)
Definition: GNSSconstants.hpp:111
gnsstk::Rinex3NavData::accuracy
RNDouble accuracy
SV accuracy (m)
Definition: Rinex3NavData.hpp:130
gnsstk::EngEphemeris::getPRNID
short getPRNID() const
Definition: EngEphemeris.cpp:619
gnsstk::BrcClockCorrection::loadData
void loadData(const std::string satSysArg, const ObsID obsIDArg, const short PRNIDArg, const CommonTime TocArg, const CommonTime TopArg, const short URAocArg, const short URAoc1Arg, const short URAoc2Arg, const bool healthyArg, const double af0Arg, const double af1Arg, const double af2Arg)
Definition: BrcClockCorrection.cpp:135
CivilTime.hpp
gnsstk::Week::week
int week
Full week number.
Definition: Week.hpp:267
gnsstk::StringUtils::asDouble
double asDouble(const std::string &s)
Definition: StringUtils.hpp:705
gnsstk::Rinex3NavData::pz
RNDouble pz
SV position.
Definition: Rinex3NavData.hpp:203
gnsstk::Rinex3NavData::reallyPutRecord
virtual void reallyPutRecord(FFStream &s) const
Definition: Rinex3NavData.cpp:253
gnsstk::EngEphemeris::getSatSys
std::string getSatSys() const noexcept
Definition: EngEphemeris.hpp:270
gnsstk::EngEphemeris::health
short health
Definition: EngEphemeris.hpp:643
gnsstk::Rinex3NavData::weeknum
short weeknum
Definition: Rinex3NavData.hpp:127
GNSSTK_RETHROW
#define GNSSTK_RETHROW(exc)
Definition: Exception.hpp:369
gnsstk::EngEphemeris::L2Pdata
short L2Pdata
Definition: EngEphemeris.hpp:644
gnsstk::Rinex3NavData::TauN
RNDouble TauN
SV clock bias (sec)
Definition: Rinex3NavData.hpp:144
gnsstk::Rinex3NavData::IODnav
RNDouble IODnav
Index of data-eph.
Definition: Rinex3NavData.hpp:155
gnsstk::RinexNavData::af2
RNDouble af2
SV clock drift rate (sec/sec**2).
Definition: RinexNavData.hpp:219
gnsstk::TimeSystem::UTC
@ UTC
Coordinated Universal Time (e.g., from NTP)
gnsstk::EngEphemeris::codeflags
short codeflags
Definition: EngEphemeris.hpp:642
gnsstk::EngEphemeris::getIODE
short getIODE() const
Definition: EngEphemeris.cpp:735
gnsstk::EngEphemeris::tracker
short tracker
Definition: EngEphemeris.hpp:634
gnsstk::RinexNavData::IODE
RNDouble IODE
Index of data-eph.
Definition: RinexNavData.hpp:211
gnsstk::Rinex3NavData::ay
RNDouble ay
Definition: Rinex3NavData.hpp:205
gnsstk::EngEphemeris::getCuc
double getCuc() const
Definition: EngEphemeris.cpp:845
gnsstk::CivilTime
Definition: CivilTime.hpp:55
gnsstk::EngEphemeris::getCrs
double getCrs() const
Definition: EngEphemeris.cpp:815
gnsstk::Rinex3NavData::af0
RNDouble af0
SV clock error (sec)
Definition: Rinex3NavData.hpp:168
gnsstk::Rinex3NavData::w
RNDouble w
Argument of perigee (rad)
Definition: Rinex3NavData.hpp:194
gnsstk::Rinex3NavData::accCode
RNDouble accCode
Accuracy code (URA, meters)
Definition: Rinex3NavData.hpp:160
GPSWeekSecond.hpp
gnsstk::EngEphemeris::getW
double getW() const
Definition: EngEphemeris.cpp:945
gnsstk::Rinex3NavData::Rinex3NavData
Rinex3NavData()
Definition: Rinex3NavData.cpp:59
gnsstk::EngEphemeris::haveSubframe
bool haveSubframe[3]
Definition: EngEphemeris.hpp:620
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::RinexSatID
Definition: RinexSatID.hpp:63
gnsstk::TimeSystem::GPS
@ GPS
GPS system time.
gnsstk::Rinex3NavData::Cus
RNDouble Cus
Sine latitude (rad)
Definition: Rinex3NavData.hpp:178
std
Definition: Angle.hpp:142
gnsstk::RinexNavData::af0
RNDouble af0
SV clock error (sec).
Definition: RinexNavData.hpp:217
gnsstk::RinexNavData::fitint
RNDouble fitint
Fit interval.
Definition: RinexNavData.hpp:247
gnsstk::RinexNavData::af1
RNDouble af1
SV clock drift (sec/sec).
Definition: RinexNavData.hpp:218
gnsstk::Rinex3NavData::dumpString
std::string dumpString() const
Write selected info (system dependent) as a single line.
Definition: Rinex3NavData.cpp:334
gnsstk::CarrierBand::Undefined
@ Undefined
Code is known to be undefined (as opposed to unknown)
gnsstk::RinexNavData::idot
RNDouble idot
Rate of inclination angle (rad/sec).
Definition: RinexNavData.hpp:246
gnsstk::Rinex3NavData::fixSF1xmitSOW
static long fixSF1xmitSOW(unsigned long sow)
Definition: Rinex3NavData.hpp:116
gnsstk::Rinex3NavData::az
RNDouble az
SV acceleration.
Definition: Rinex3NavData.hpp:205
gnsstk::EngEphemeris::getM0
double getM0() const
Definition: EngEphemeris.cpp:875
BDSWeekSecond.hpp
gnsstk::EngEphemeris::weeknum
short weeknum
Definition: EngEphemeris.hpp:640
gnsstk::BrcKeplerOrbit::loadData
void loadData(const std::string satSysArg, const ObsID obsIDArg, const short PRNIDArg, const CommonTime beginFitArg, const CommonTime endFitArg, const CommonTime ToeArg, const short URAoeArg, const bool healthyArg, const double CucArg, const double CusArg, const double CrcArg, const double CrsArg, const double CicArg, const double CisArg, const double M0Arg, const double dnArg, const double dndotArg, const double eccArg, const double AArg, const double AhalfArg, const double AdotArg, const double OMEGA0Arg, const double i0Arg, const double wArg, const double OMEGAdotARg, const double idotArg)
General purpose means to load data into object.
Definition: BrcKeplerOrbit.cpp:136
gnsstk::RinexNavData::i0
RNDouble i0
Inclination (rad).
Definition: RinexNavData.hpp:243
gnsstk::Rinex3NavData::reallyGetRecord
virtual void reallyGetRecord(FFStream &s)
Definition: Rinex3NavData.cpp:190
GNSSTK_THROW
#define GNSSTK_THROW(exc)
Definition: Exception.hpp:366
gnsstk::RinexNavData::Cis
RNDouble Cis
Sine inclination (rad).
Definition: RinexNavData.hpp:231
gnsstk::EngEphemeris::orbit
BrcKeplerOrbit orbit
Orbit parameters.
Definition: EngEphemeris.hpp:666
gnsstk::EngEphemeris::getAccuracy
double getAccuracy() const
Definition: EngEphemeris.cpp:685
gnsstk::Rinex3NavData::vy
RNDouble vy
Definition: Rinex3NavData.hpp:204
gnsstk::Rinex3NavHeader::fileSys
std::string fileSys
File system string.
Definition: Rinex3NavHeader.hpp:180
gnsstk::Rinex3NavData::Cis
RNDouble Cis
Sine inclination (rad)
Definition: Rinex3NavData.hpp:182
gnsstk::Rinex3NavData::sat
RinexSatID sat
RinexSatID (from PRNID & satSys)
Definition: Rinex3NavData.hpp:125
gnsstk::Rinex3NavData::xmitTime
long xmitTime
Time of subframe 1-3 (sec of week)
Definition: Rinex3NavData.hpp:126
gnsstk::EngEphemeris::getCic
double getCic() const
Definition: EngEphemeris.cpp:855
gnsstk::EngEphemeris::getAf0
double getAf0() const
Definition: EngEphemeris.cpp:765
QZSWeekSecond.hpp
gnsstk::EngEphemeris::getCus
double getCus() const
Definition: EngEphemeris.cpp:805
gnsstk::EngEphemeris::getCodeFlags
short getCodeFlags() const
Definition: EngEphemeris.cpp:675
gnsstk::Rinex3NavData::GammaN
RNDouble GammaN
SV relative frequency bias.
Definition: Rinex3NavData.hpp:145
gnsstk::EngEphemeris::getI0
double getI0() const
Definition: EngEphemeris.cpp:935
gnsstk::TimeSystem::BDT
@ BDT
BeiDou system Time.
gnsstk::EngEphemeris::getToe
double getToe() const
Definition: EngEphemeris.cpp:865
gnsstk::EngEphemeris::tlm_message
unsigned short tlm_message[3]
Definition: EngEphemeris.hpp:631
gnsstk::TrackingCode::Undefined
@ Undefined
Code is known to be undefined (as opposed to unknown)
GALWeekSecond.hpp
gnsstk::EngEphemeris::getOmegaDot
double getOmegaDot() const
Definition: EngEphemeris.cpp:955
gnsstk::Rinex3NavData::idot
RNDouble idot
Rate of inclination angle (rad/sec)
Definition: Rinex3NavData.hpp:196
TimeString.hpp
gnsstk::RinexNavData::Ahalf
RNDouble Ahalf
SQRT of semi-major axis (m**1/2).
Definition: RinexNavData.hpp:241
gnsstk::Rinex3NavData::M0
RNDouble M0
Mean anomaly (rad)
Definition: Rinex3NavData.hpp:188
gnsstk::FormattedDouble::val
double val
The value as read or to be formatted.
Definition: FormattedDouble.hpp:181
gnsstk::Rinex3NavData::getPRNEpoch
void getPRNEpoch(Rinex3NavStream &strm)
Definition: Rinex3NavData.cpp:744


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