PNBGLOCNavDataFactory.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 //
28 // This software was developed by Applied Research Laboratories at the
29 // University of Texas at Austin, under contract to an agency or agencies
30 // within the U.S. Department of Defense. The U.S. Government retains all
31 // rights to use, duplicate, distribute, disclose, or release this software.
32 //
33 // Pursuant to DoD Directive 523024
34 //
35 // DISTRIBUTION STATEMENT A: This software has been approved for public
36 // release, distribution is unlimited.
37 //
38 //==============================================================================
39 #include "DebugTrace.hpp"
41 #include "GLOCBits.hpp"
42 #include "GLOCNavAlm.hpp"
43 #include "GLOCNavEph.hpp"
44 #include "GLOCNavHealth.hpp"
45 #include "GLOCNavIono.hpp"
46 #if 0
47 #include "GLOCNavISC.hpp"
48 #include "GLOCNavTimeOffset.hpp"
49 #endif
50 #include "GLOCNavUT1TimeOffset.hpp"
51 #include "GLONASSTime.hpp"
52 #include "CivilTime.hpp"
53 #include "YDSTime.hpp"
54 #include "TimeString.hpp"
55 #include "DebugTrace.hpp"
56 
57 using namespace std;
58 using namespace gnsstk::gloc;
59 
60 namespace gnsstk
61 {
62  PNBGLOCNavDataFactory ::
63  PNBGLOCNavDataFactory()
64  : almDOY(CommonTime::BEGINNING_OF_TIME),
65  pendingAlms(false)
66  {
67  }
68 
69 
72  double cadence)
73  {
75  static bool printed = false;
76  if ((navIn->getNavID().navType != NavType::GloCivilC) ||
77  (navIn->getNumBits() != 300))
78  {
79  DEBUGTRACE("nope, failed. " << navIn->getNavID().navType << " "
80  << navIn->getNumBits());
81  // This class processes only GLONASS L3OCD NAV.
82  return false;
83  }
84  bool rv = true;
85  try
86  {
87  unsigned long msgType = navIn->asUnsignedLong(
89  DEBUGTRACE("msgType = " << msgType);
90  bool checkMsg = false, expMsg = false;
91  switch (navValidity)
92  {
94  checkMsg = true;
95  expMsg = true;
96  break;
98  checkMsg = true;
99  expMsg = false;
100  break;
101  }
102  if (checkMsg)
103  {
104  // first check the Preamble
105  unsigned long preamble = navIn->asUnsignedLong(
107  bool valid = (preamble == valPreamble);
108  DEBUGTRACE("Checking message validity = " << valid
109  << " preamble = " << hex << preamble);
110  if (valid != expMsg)
111  {
112  return true;
113  }
115  // Now check the CRC which is a bit more
116  // computationally involved. It should be the last
117  // check done here unless another even more
118  // computation-heavy validation is added (unlikely).
119  }
120  DEBUGTRACE("doing switch");
121  switch (msgType)
122  {
123  case 10:
124  case 11:
125  case 12:
126  DEBUGTRACE("eph");
127  // immediate (ephemeris) data
128  rv = processEph(msgType, navIn, navOut);
129  break;
130  case 20:
131  DEBUGTRACE("alm");
132  rv = processAlm(navIn, navOut);
133  break;
134  case 25:
135  DEBUGTRACE("earth");
136  // Earth rotation, iono model, time offset
137  processEarth(navIn, navOut);
138  break;
139  case 31:
140  case 32:
141  DEBUGTRACE("ltdmp");
142  processLTDMP(msgType, navIn);
143  break;
144  default:
145  DEBUGTRACE("ignore");
146  // Ignore everything else.
147  rv = true;
148  break;
149  }
150  if (rv && processHea)
151  {
152  rv = processHealth(navIn, navOut);
153  }
154  }
155  catch (Exception& exc)
156  {
157  rv = false;
158  cerr << exc << endl;
159  }
160  catch (std::exception& exc)
161  {
162  rv = false;
163  cerr << exc.what() << endl;
164  }
165  catch (...)
166  {
167  rv = false;
168  cerr << "Unknown exception" << endl;
169  }
170  return rv;
171  }
172 
173 
176  {
178  // In the interest of not wasting time in the 99% case,
179  // double-checking the nav message size and type. This could
180  // result in a crash if a user calls this method directly
181  // with garbage, but that's a trade-off I'm willing to make
182  // rather than encumber the other 99% with multiple identical
183  // if tests on every message.
184  navOut.xmit = navIn->getTransmitTime();
185  navOut.preamble = navIn->asUnsignedLong(fsbPreamble, fnbPreamble,
186  fscPreamble);
187  navOut.TS = navIn->asUnsignedLong(fsbTS, fnbTS, fscTS);
188  navOut.svid = navIn->asUnsignedLong(fsbj, fnbj, fscj);
189  navOut.svUnhealthy = navIn->asBool(fsbHj);
190  navOut.dataInvalid = navIn->asBool(fsblj);
191  DEBUGTRACE("svUnhealthy=" << navOut.svUnhealthy);
192  DEBUGTRACE("dataInvalid=" << navOut.dataInvalid);
193  navOut.P1 = navIn->asUnsignedLong(fsbP1, fnbP1, fscP1);
194  navOut.P2 = navIn->asBool(fsbP2);
195  navOut.KP = navIn->asUnsignedLong(fsbKP, fnbKP, fscKP);
196  navOut.A = navIn->asBool(fsbA);
197  return true;
198  }
199 
200 
203  {
205  NavSatelliteID key(navIn->getsatSys().id, navIn->getsatSys(),
206  navIn->getobsID(), navIn->getNavID());
207  DEBUGTRACE("key = " << key);
208  if (processIono)
209  {
210  DEBUGTRACE("iono");
211  NavDataPtr p0 = std::make_shared<GLOCNavIono>();
212  p0->timeStamp = navIn->getTransmitTime();
213  p0->signal = NavMessageID(key, NavMessageType::Iono);
214  GLOCNavIono *iono = dynamic_cast<GLOCNavIono*>(p0.get());
215  iono->peakTECF2 = navIn->asUnsignedDouble(isbcA,inbcA,isccA);
216  iono->solarIndex = navIn->asUnsignedDouble(isbcF107,inbcF107,isccF107);
217  iono->geoIndex = navIn->asUnsignedDouble(isbcAp,inbcAp,isccAp);
218  navOut.push_back(p0);
219  }
220  if (processTim && timeAcc[key].isValid())
221  {
222  DEBUGTRACE("time");
223  NavDataPtr p0 = std::make_shared<GLOCNavUT1TimeOffset>();
224  GLOCNavUT1TimeOffset *to = dynamic_cast<GLOCNavUT1TimeOffset*>(
225  p0.get());
226  to->NB = navIn->asUnsignedLong(isbNB, inbNB, iscNB);
227  to->B0 = navIn->asSignMagDouble(isbB0,inbB0,iscB0);
228  to->B1 = navIn->asSignMagDouble(isbB1,inbB1,iscB1);
229  // see the warning in GLOCNavUT1TimeOffset
230  to->B2 = navIn->asSignMagDouble(isbB2,inbB2,iscB2) / 2.0;
231  // Table 5.5 indicates this is signed, strangely enough.
232  to->UTCTAI = navIn->asSignMagLong(isbUTCTAI, inbUTCTAI, iscUTCTAI);
233  to->timeStamp = navIn->getTransmitTime();
234  // reference time is always the start of the day
235  to->refTime = GLONASSTime(timeAcc[key].N4, to->NB);
237  navOut.push_back(p0);
238  }
239  return true;
240  }
241 
242 
245  {
246  if (processHea)
247  {
248  NavSatelliteID key(navIn->getsatSys().id, navIn->getsatSys(),
249  navIn->getobsID(), navIn->getNavID());
250  NavDataPtr p0 = std::make_shared<GLOCNavHealth>();
251  key.sat.id = navIn->asUnsignedLong(fsbj, fnbj, fscj);
252  p0->timeStamp = navIn->getTransmitTime();
253  p0->signal = NavMessageID(key, NavMessageType::Health);
254  dynamic_cast<GLOCNavHealth*>(p0.get())->Hj = navIn->asBool(fsbHj);
255  dynamic_cast<GLOCNavHealth*>(p0.get())->lj = navIn->asBool(fsblj);
256  navOut.push_back(p0);
257  }
258  // No reason to return false in this code so far, maybe later.
259  return true;
260  }
261 
262 
264  processEph(unsigned long stringID, const PackedNavBitsPtr& navIn,
265  NavDataPtrList& navOut)
266  {
268  NavSatelliteID key(navIn->getsatSys().id, navIn->getsatSys(),
269  navIn->getobsID(), navIn->getNavID());
270  if ((stringID < 10) || (stringID > 12))
271  {
272  DEBUGTRACE("not an eph stringID");
273  return false; // not actually part of the ephemeris.
274  }
275  if (stringID == 10)
276  {
277  // if (PNBNavDataFactory::processISC)
278  // {
279  // NavDataPtr p2 = std::make_shared<GLOCNavISC>();
280  // GLOCNavISC *isc = dynamic_cast<GLOCNavISC*>(p2.get());
281  // isc->timeStamp = navIn->getTransmitTime();
282  // isc->signal = NavMessageID(key, NavMessageType::ISC);
283  // isc->isc = navIn->asSignMagDouble(esbdtaun,enbdtaun,escdtaun);
284  // navOut.push_back(p2);
285  // }
287  {
288  timeAcc[key].setN4(navIn->asUnsignedLong(esbN4,enbN4,escN4));
289  }
290  }
292  {
293  DEBUGTRACE("ephs not requested");
294  DEBUGTRACE("processEph = " << PNBNavDataFactory::processEph);
295  DEBUGTRACE("processAlm = " << PNBNavDataFactory::processAlm);
296  DEBUGTRACE("processHea = " << PNBNavDataFactory::processHea);
297  DEBUGTRACE("processTim = " << PNBNavDataFactory::processTim);
298  DEBUGTRACE("processIono = " << PNBNavDataFactory::processIono);
299  DEBUGTRACE("processISC = " << PNBNavDataFactory::processISC);
300  // User doesn't want ephemerides so don't do any processing.
301  return true;
302  }
303  if (ephAcc.find(key) == ephAcc.end())
304  {
305  DEBUGTRACE("new ephemeris");
306  // set up a new ephemeris
307  ephAcc[key].resize(3); // we only store strings 10-12
308  ephAcc[key][stringID-firstEphString] = navIn;
309  // nothing in navOut yet and no further processing because
310  // we only have one of four strings at this point.
311  return true;
312  }
313  std::vector<PackedNavBitsPtr> &ephS(ephAcc[key]);
314  ephS[stringID-firstEphString] = navIn;
315  DEBUGTRACE("stored ephS[" << (stringID-firstEphString) << "] for "<< key);
316  // stop processing if we don't have a complete, consecutive
317  // set of strings
318  if (!ephS[str10] || !ephS[str11] || !ephS[str12] ||
319  (ephS[str10]->getNumBits() != 300) ||
320  (ephS[str11]->getNumBits() != 300) ||
321  (ephS[str12]->getNumBits() != 300) ||
322  (ephS[str11]->getTransmitTime()-ephS[str10]->getTransmitTime() != 3)||
323  (ephS[str12]->getTransmitTime()-ephS[str11]->getTransmitTime() != 3))
324  {
325  DEBUGTRACE("!ephS[str10]=" << (!ephS[str10]));
326  DEBUGTRACE("!ephS[str11]=" << (!ephS[str11]));
327  DEBUGTRACE("!ephS[str12]=" << (!ephS[str12]));
328  if (ephS[str10] && ephS[str11] && ephS[str12])
329  {
330  DEBUGTRACE("ephS[str10]->getNumBits()=" << ephS[str10]->getNumBits());
331  DEBUGTRACE("ephS[str11]->getNumBits()=" << ephS[str11]->getNumBits());
332  DEBUGTRACE("ephS[str12]->getNumBits()=" << ephS[str12]->getNumBits());
333  DEBUGTRACE("dT(11,10)=" << (ephS[str11]->getTransmitTime()-ephS[str10]->getTransmitTime()));
334  DEBUGTRACE("dT(12,11)=" << (ephS[str12]->getTransmitTime()-ephS[str11]->getTransmitTime()));
335  }
336  return true;
337  }
338  DEBUGTRACE("Sufficient data for ephemeris. Proceeding");
339  NavDataPtr p0 = std::make_shared<GLOCNavEph>();
340  GLOCNavEph *eph = dynamic_cast<GLOCNavEph*>(p0.get());
342  if (!processHeader(ephS[str10], eph->header))
343  {
344  return false;
345  }
346  if (!processHeader(ephS[str11], eph->header11))
347  {
348  return false;
349  }
350  if (!processHeader(ephS[str12], eph->header12))
351  {
352  return false;
353  }
354  eph->timeStamp = eph->header.xmit;
355  DEBUGTRACE("N4 bits: " << esiN4 << " " << esbN4 << " " << enbN4 << " " << escN4);
356  DEBUGTRACE("NT bits: " << esiNT << " " << esbNT << " " << enbNT << " " << escNT);
357  DEBUGTRACE("tb bits: " << esitb << " " << esbtb << " " << enbtb << " " << esctb);
358  DEBUGTRACE("tb: " << hex << ephS[esitb]->asUnsignedLong(82,10,1));
359  eph->N4 = ephS[esiN4]->asUnsignedLong(esbN4, enbN4, escN4);
360  eph->NT = ephS[esiNT]->asUnsignedLong(esbNT, enbNT, escNT);
361  eph->Mj = static_cast<GLOCSatType>(
362  ephS[esiMj]->asUnsignedLong(esbMj, enbMj, escMj));
363  eph->PS = ephS[esiPS]->asUnsignedLong(esbPS, enbPS, escPS);
364  eph->tb = ephS[esitb]->asUnsignedLong(esbtb, enbtb, esctb);
365  DEBUGTRACE("N4 = " << (unsigned)eph->N4);
366  DEBUGTRACE("NT = " << eph->NT);
367  DEBUGTRACE("tb (string " << (esitb+firstEphString) << ") = " << eph->tb);
368  eph->Toe = GLONASSTime(eph->N4, eph->NT, eph->tb, TimeSystem::GLO);
369  // change toe from Moscow Time to UTC(SU) aka TimeSystem::GLO
370  eph->Toe -= 10800;
372  eph->EjE = ephS[esiEjE]->asUnsignedLong(esbEjE, enbEjE, escEjE);
373  eph->EjT = ephS[esiEjT]->asUnsignedLong(esbEjT, enbEjT, escEjT);
374  eph->RjE = static_cast<GLOCRegime>(
375  ephS[esiRjE]->asUnsignedLong(esbRjE, enbRjE, escRjE));
376  eph->RjT = static_cast<GLOCRegime>(
377  ephS[esiRjT]->asUnsignedLong(esbRjT, enbRjT, escRjT));
378  eph->FjE = ephS[esiFjE]->asSignMagLong(esbFjE, enbFjE, escFjE);
379  eph->FjT = ephS[esiFjT]->asSignMagLong(esbFjT, enbFjT, escFjT);
380  eph->clkBias = ephS[esitauj]->asSignMagDouble(esbtauj, enbtauj, esctauj);
381  eph->freqBias = ephS[esigammaj]->asSignMagDouble(
384  eph->driftRate = ephS[esiBetaj]->asSignMagDouble(
386  eph->tauc = ephS[esitauc]->asSignMagDouble(esbtauc, enbtauc, esctauc);
387  eph->taucdot = ephS[esitaucdot]->asSignMagDouble(
389  eph->pos[0]=ephS[esixj]->asSignMagDouble(esbxj,enbxj,escxj);
390  eph->pos[1]=ephS[esiyj]->asSignMagDouble(esbyj,enbyj,escyj);
391  eph->pos[2]=ephS[esizj]->asSignMagDouble(esbzj,enbzj,esczj);
392  eph->vel[0]=ephS[esixjp]->asSignMagDouble(esbxjp,enbxjp,escxjp);
393  eph->vel[1]=ephS[esiyjp]->asSignMagDouble(esbyjp,enbyjp,escyjp);
394  eph->vel[2]=ephS[esizjp]->asSignMagDouble(esbzjp,enbzjp,esczjp);
395  eph->acc[0]=ephS[esixjpp]->asSignMagDouble(esbxjpp,enbxjpp,escxjpp);
396  eph->acc[1]=ephS[esiyjpp]->asSignMagDouble(esbyjpp,enbyjpp,escyjpp);
397  eph->acc[2]=ephS[esizjpp]->asSignMagDouble(esbzjpp,enbzjpp,esczjpp);
398  eph->apcOffset[0] = ephS[esiDeltaxjpc]->asSignMagDouble(
400  eph->apcOffset[1] = ephS[esiDeltayjpc]->asSignMagDouble(
402  eph->apcOffset[2] = ephS[esiDeltazjpc]->asSignMagDouble(
404  eph->tauDelta = ephS[esiDeltataujL3]->asSignMagDouble(
406  eph->tauGPS = ephS[esiTauGPS]->asSignMagDouble(
408  if (ltdmpAcc[key].tbMatch(eph->tb))
409  {
410  eph->ltdmp = ltdmpAcc[key];
411  }
412  // Always set the "main" health according to all health info,
413  // since it's going to be the one being referenced 99% of the
414  // time. Copy the value into the other headers for
415  // consistency.
416  eph->header.health =
417  eph->header11.health =
418  eph->header12.health =
419  ((eph->header.svUnhealthy || eph->header11.svUnhealthy ||
420  eph->header12.svUnhealthy)
423 
424 
425  eph->fixFit();
426  navOut.push_back(p0);
427  // Clear out the broadcast ephemeris that's been processed.
428  ephAcc.erase(key);
429  // cerr << "navOut.size()=" << navOut.size() << endl
430  // << key.sat << " Toe="
431  // << printTime(eph->Toe, "%Y/%02m/%02d %02H:%02M:%02S %P") << endl
432  // << key.sat << " tb=" << eph->tb << " tb*interval="
433  // << eph->tb*interval << endl
434  // << key.sat << " toe.sod=" << toe.sod << endl
435  // << key.sat << " interval=" << eph->interval << " (" << interval
436  // << ")" << endl
437  // << key.sat << " P1=" << eph->P1 << endl;
438  return true;
439  }
440 
441 
444  {
446  SatID xmitSat(navIn->getsatSys());
447  // Key used for data accumulating, which we don't separate by
448  // subject satellite.
449  NavSatelliteID key(0, xmitSat, navIn->getobsID(), navIn->getNavID());
451  {
452  // User doesn't want almanacs so don't do any processing.
453  return true;
454  }
455  NavDataPtr p0 = std::make_shared<GLOCNavAlm>();
456  GLOCNavAlm *alm = dynamic_cast<GLOCNavAlm*>(p0.get());
458  if (!processHeader(navIn, alm->header))
459  {
460  return false;
461  }
462  alm->timeStamp = alm->header.xmit;
463  alm->signal.sat.id = alm->header.svid;
464  alm->orbitType = static_cast<GLOCOrbitType>(
465  navIn->asUnsignedLong(asbTO, anbTO, ascTO));
466  alm->numSVs = navIn->asUnsignedLong(asbNS, anbNS, ascNS);
467  alm->aoa = navIn->asUnsignedLong(asbE, anbE, ascE);
468  alm->NA = navIn->asUnsignedLong(asbNA, anbNA, ascNA);
469  alm->statusReg = navIn->asUnsignedLong(asbSR, anbSR, ascSR);
470  alm->satType = static_cast<GLOCSatType>(
471  navIn->asUnsignedLong(asbM, anbM, ascM));
472  alm->tau = navIn->asSignMagDouble(asbtau, anbtau, asctau);
473  alm->lambda = navIn->asSignMagDouble(asblambda, anblambda, asclambda);
474  alm->tLambda = navIn->asUnsignedDouble(
476  alm->deltai = navIn->asSignMagDouble(asbDeltai, anbDeltai, ascDeltai);
477  alm->ecc = navIn->asSignMagDouble(asbepsilon, anbepsilon, ascepsilon);
478  alm->omega = navIn->asSignMagDouble(asbomega, anbomega, ascomega);
479  alm->deltaT = navIn->asSignMagDouble(asbDeltaT, anbDeltaT, ascDeltaT);
480  alm->deltaTdot = navIn->asSignMagDouble(
482  alm->header.health =
484  int N4 = 0;
485  if (timeAcc[key].isValid())
486  {
487  N4 = timeAcc[key].N4;
488  }
489  else
490  {
491  // No ephemeris yet to supply the N4 term, make a best
492  // guess based on the transmit time.
493  GLONASSTime getN4(alm->timeStamp);
494  N4 = getN4.epoch;
495  }
496  alm->Toa = gnsstk::GLONASSTime(N4, alm->NA, alm->tLambda,
498  alm->fixFit();
499  navOut.push_back(p0);
500  return true;
501  }
502 
503 
505  processLTDMP(unsigned long stringID,
506  const PackedNavBitsPtr& navIn)
507  {
509  uint16_t tb;
510  tb = navIn->asUnsignedLong(lsbtb, lnbtb, lsctb);
511  DEBUGTRACE("tb (string " << stringID << ") = " << tb);
512  NavSatelliteID key(navIn->getsatSys().id, navIn->getsatSys(),
513  navIn->getobsID(), navIn->getNavID());
514  GLOCNavLTDMP *ltdmp = &ltdmpAcc[key];
515  switch (stringID)
516  {
517  case 31:
518  ltdmp->tb31 = tb;
519  if (!processHeader(navIn, ltdmp->header31))
520  {
521  return false;
522  }
523  ltdmp->dax0 = navIn->asSignMagDouble(lsbdax0, lnbdax0, lscdax0);
524  ltdmp->day0 = navIn->asSignMagDouble(lsbday0, lnbday0, lscday0);
525  ltdmp->daz0 = navIn->asSignMagDouble(lsbdaz0, lnbdaz0, lscdaz0);
526  ltdmp->ax1 = navIn->asSignMagDouble(lsbax1, lnbax1, lscax1);
527  ltdmp->ay1 = navIn->asSignMagDouble(lsbay1, lnbay1, lscay1);
528  ltdmp->az1 = navIn->asSignMagDouble(lsbaz1, lnbaz1, lscaz1);
529  ltdmp->ax2 = navIn->asSignMagDouble(lsbax2, lnbax2, lscax2);
530  ltdmp->ay2 = navIn->asSignMagDouble(lsbay2, lnbay2, lscay2);
531  ltdmp->az2 = navIn->asSignMagDouble(lsbaz2, lnbaz2, lscaz2);
532  break;
533  case 32:
534  ltdmp->tb32 = tb;
535  if (!processHeader(navIn, ltdmp->header32))
536  {
537  return false;
538  }
539  ltdmp->ax3 = navIn->asSignMagDouble(lsbax3, lnbax3, lscax3);
540  ltdmp->ay3 = navIn->asSignMagDouble(lsbay3, lnbay3, lscay3);
541  ltdmp->az3 = navIn->asSignMagDouble(lsbaz3, lnbaz3, lscaz3);
542  ltdmp->ax4 = navIn->asSignMagDouble(lsbax4, lnbax4, lscax4);
543  ltdmp->ay4 = navIn->asSignMagDouble(lsbay4, lnbay4, lscay4);
544  ltdmp->az4 = navIn->asSignMagDouble(lsbaz4, lnbaz4, lscaz4);
545  break;
546  default:
547  return false;
548  }
549  return true;
550  }
551 
552 
555  {
557  timeAcc.clear();
558  ephAcc.clear();
559  almAcc.clear();
560  }
561 
562 
564  setN4(unsigned v)
565  {
566  N4 = v;
567  }
568 
569 
572  {
573  return N4.is_valid();
574  }
575 
576 } // namespace gnsstk
gnsstk::gloc::lsbaz1
@ lsbaz1
Definition: GLOCBits.hpp:458
gnsstk::gloc::isbB1
@ isbB1
Definition: GLOCBits.hpp:401
gnsstk::NavDataPtr
std::shared_ptr< NavData > NavDataPtr
Factories instantiate these in response to find() requests.
Definition: NavData.hpp:62
gnsstk::GLOCNavEph::Mj
GLOCSatType Mj
What satellite j is and what it transmits.
Definition: GLOCNavEph.hpp:138
gnsstk::gloc::inbcAp
@ inbcAp
Definition: GLOCBits.hpp:418
YDSTime.hpp
gnsstk::gloc::esizj
@ esizj
Definition: GLOCBits.hpp:226
gnsstk::GLOCNavEph::RjT
GLOCRegime RjT
Regime for generation of clock data.
Definition: GLOCNavEph.hpp:144
gnsstk::gloc::lsbax4
@ lsbax4
Definition: GLOCBits.hpp:486
gnsstk::gloc::esitb
@ esitb
Definition: GLOCBits.hpp:150
gnsstk::gloc::esiNT
@ esiNT
Definition: GLOCBits.hpp:135
gnsstk::gloc::ascNA
@ ascNA
Definition: GLOCBits.hpp:319
gnsstk::NavMessageID
Class used to identify/categorize navigation message data.
Definition: NavMessageID.hpp:52
gnsstk::gloc::escyjpp
@ escyjpp
Definition: GLOCBits.hpp:260
gnsstk::gloc::iscB1
@ iscB1
Definition: GLOCBits.hpp:403
gnsstk::gloc::lnbdax0
@ lnbdax0
Definition: GLOCBits.hpp:439
gnsstk::GLOCNavEph::vel
Triple vel
Satellite velocity at tb in km/s.
Definition: GLOCNavEph.hpp:154
gnsstk::PNBGLOCNavDataFactory::resetState
void resetState() override
Definition: PNBGLOCNavDataFactory.cpp:554
gnsstk::GLOCNavHeader::svid
uint8_t svid
Subject SV ID (j).
Definition: GLOCNavHeader.hpp:86
gnsstk::GLOCNavEph
Definition: GLOCNavEph.hpp:57
gnsstk::gloc::ascepsilon
@ ascepsilon
Definition: GLOCBits.hpp:347
gnsstk::GLOCNavUT1TimeOffset
Definition: GLOCNavUT1TimeOffset.hpp:58
gnsstk::gloc::lscax3
@ lscax3
Definition: GLOCBits.hpp:476
gnsstk::gloc::lscax2
@ lscax2
Definition: GLOCBits.hpp:464
gnsstk::PNBGLOCNavDataFactory::ephAcc
std::map< NavSatelliteID, std::vector< PackedNavBitsPtr > > ephAcc
Definition: PNBGLOCNavDataFactory.hpp:173
gnsstk::SatID::id
int id
Satellite identifier, e.g. PRN.
Definition: SatID.hpp:154
gnsstk::PackedNavBitsPtr
std::shared_ptr< PackedNavBits > PackedNavBitsPtr
Managed pointer for passing PackedNavBits around.
Definition: PackedNavBits.hpp:66
gnsstk::gloc::esbFjT
@ esbFjT
Definition: GLOCBits.hpp:181
gnsstk::GLOCNavLTDMP::header32
GLOCNavHeader header32
Header (incl xmit time) data from string 32.
Definition: GLOCNavLTDMP.hpp:79
gnsstk::gloc::lnbax1
@ lnbax1
Definition: GLOCBits.hpp:451
gnsstk::gloc::enbzj
@ enbzj
Definition: GLOCBits.hpp:228
gnsstk::gloc::inbUTCTAI
@ inbUTCTAI
Definition: GLOCBits.hpp:422
gnsstk::GLONASSTime::epoch
unsigned epoch
Number of leap years since 1996 (aka N4).
Definition: GLONASSTime.hpp:164
gnsstk::gloc::iscB0
@ iscB0
Definition: GLOCBits.hpp:399
gnsstk::gloc::enbyj
@ enbyj
Definition: GLOCBits.hpp:223
gnsstk::GLOCNavEph::PS
uint8_t PS
Number of strings from this type 10 to the next.
Definition: GLOCNavEph.hpp:139
gnsstk::GLOCNavAlm::numSVs
unsigned numSVs
Number of SVs in complete almanac (NS).
Definition: GLOCNavAlm.hpp:131
gnsstk::gloc::esbxjpp
@ esbxjpp
Definition: GLOCBits.hpp:253
gnsstk::GLOCNavAlm::orbitType
GLOCOrbitType orbitType
Orbit type.
Definition: GLOCNavAlm.hpp:130
gnsstk::gloc::anbNS
@ anbNS
Definition: GLOCBits.hpp:310
gnsstk::gloc::anbDeltai
@ anbDeltai
Definition: GLOCBits.hpp:342
gnsstk::gloc::inbcA
@ inbcA
Definition: GLOCBits.hpp:410
gnsstk::gloc::enbFjE
@ enbFjE
Definition: GLOCBits.hpp:177
gnsstk::gloc::lnbday0
@ lnbday0
Definition: GLOCBits.hpp:443
gnsstk::gloc::escRjE
@ escRjE
Definition: GLOCBits.hpp:168
gnsstk::GLOCNavEph::acc
Triple acc
Satellite acceleration at tb in km/s**2.
Definition: GLOCNavEph.hpp:155
gnsstk::gloc::asbM
@ asbM
Sat type and signal.
Definition: GLOCBits.hpp:325
gnsstk::gloc::escMj
@ escMj
Definition: GLOCBits.hpp:143
gnsstk::PNBGLOCNavDataFactory::TimeMeta::isValid
bool isValid()
Return true if all data fields are valid.
Definition: PNBGLOCNavDataFactory.cpp:571
gnsstk::gloc::iscUTCTAI
@ iscUTCTAI
Definition: GLOCBits.hpp:423
gnsstk::gloc::fnbTS
@ fnbTS
Definition: GLOCBits.hpp:86
gnsstk::gloc::lsbay4
@ lsbay4
Definition: GLOCBits.hpp:490
gnsstk::GLOCNavEph::EjT
uint8_t EjT
Age of clock (6-hour intervals).
Definition: GLOCNavEph.hpp:142
gnsstk::gloc::enbBetaj
@ enbBetaj
Definition: GLOCBits.hpp:197
gnsstk::gloc::enbEjT
@ enbEjT
Definition: GLOCBits.hpp:162
gnsstk::gloc::inbNB
@ inbNB
Definition: GLOCBits.hpp:370
gnsstk::gloc::enbFjT
@ enbFjT
Definition: GLOCBits.hpp:182
gnsstk::GLOCNavIono::geoIndex
double geoIndex
Geomagnetic activity index value (c_Ap).
Definition: GLOCNavIono.hpp:84
gnsstk::gloc::isbcF107
@ isbcF107
Definition: GLOCBits.hpp:413
gnsstk::gloc::escNT
@ escNT
Definition: GLOCBits.hpp:138
gnsstk::BEGINNING_OF_TIME
const Epoch BEGINNING_OF_TIME(CommonTime::BEGINNING_OF_TIME)
Earliest representable Epoch.
gnsstk::gloc::asbtau
@ asbtau
rough time correction
Definition: GLOCBits.hpp:329
gnsstk::GLOCNavEph::EjE
uint8_t EjE
Age of ephemeris (6-hour intervals).
Definition: GLOCNavEph.hpp:141
gnsstk::gloc::lsbaz4
@ lsbaz4
Definition: GLOCBits.hpp:494
gnsstk::gloc::escPS
@ escPS
Definition: GLOCBits.hpp:148
gnsstk::gloc::valPreamble
@ valPreamble
Definition: GLOCBits.hpp:79
gnsstk::gloc::lnbay3
@ lnbay3
Definition: GLOCBits.hpp:479
gnsstk::gloc::enbyjp
@ enbyjp
Definition: GLOCBits.hpp:238
gnsstk::gloc::lnbaz4
@ lnbaz4
Definition: GLOCBits.hpp:495
gnsstk::gloc::esiEjE
@ esiEjE
Definition: GLOCBits.hpp:155
gnsstk::GLOCNavEph::pos
Triple pos
Satellite position at tb in km.
Definition: GLOCNavEph.hpp:153
gnsstk::GLOCNavIono
Class containing data elements unique to GPS LNav ionospheric data.
Definition: GLOCNavIono.hpp:50
gnsstk::gloc::fsbKP
@ fsbKP
UTC planned corr start bit.
Definition: GLOCBits.hpp:109
gnsstk::gloc::esczjpp
@ esczjpp
Definition: GLOCBits.hpp:265
gnsstk::gloc::anbM
@ anbM
Definition: GLOCBits.hpp:326
gnsstk::gloc::inbB0
@ inbB0
Definition: GLOCBits.hpp:398
gnsstk::gloc::anbTO
@ anbTO
Definition: GLOCBits.hpp:306
gnsstk::GLOCNavEph::Toe
CommonTime Toe
Reference time, combining N4, NT and tb.
Definition: GLOCNavEph.hpp:135
gnsstk::gloc::esbxj
@ esbxj
Definition: GLOCBits.hpp:217
gnsstk::GLOCNavEph::tauDelta
double tauDelta
Offset of L3OCP time to L3OCD time.
Definition: GLOCNavEph.hpp:159
gnsstk::GLOCNavEph::RjE
GLOCRegime RjE
Regime for generation of ephemeris data.
Definition: GLOCNavEph.hpp:143
gnsstk::GLOCNavData::header
GLOCNavHeader header
Common data.
Definition: GLOCNavData.hpp:65
gnsstk::GLOCNavLTDMP::day0
double day0
Definition: GLOCNavLTDMP.hpp:86
gnsstk::gloc::fsbP1
@ fsbP1
Definition: GLOCBits.hpp:101
gnsstk::GLOCNavHeader::dataInvalid
bool dataInvalid
Data validity flag (lj, false=valid).
Definition: GLOCNavHeader.hpp:88
gnsstk::NavSatelliteID
Definition: NavSatelliteID.hpp:57
gnsstk::GLOCNavUT1TimeOffset::B1
double B1
Time drift in s/s.
Definition: GLOCNavUT1TimeOffset.hpp:104
gnsstk::gloc::ascNS
@ ascNS
Definition: GLOCBits.hpp:311
gnsstk::gloc::lsctb
@ lsctb
Definition: GLOCBits.hpp:436
gnsstk::gloc::esctauc
@ esctauc
Definition: GLOCBits.hpp:203
gnsstk::GLOCNavLTDMP::tb31
unsigned long tb31
Reference instant in Moscow time for string 31.
Definition: GLOCNavLTDMP.hpp:80
gnsstk::gloc::fsbP2
@ fsbP2
Definition: GLOCBits.hpp:105
gnsstk::gloc::str12
@ str12
Definition: GLOCBits.hpp:56
gnsstk::gloc::anbDeltaTdot
@ anbDeltaTdot
Definition: GLOCBits.hpp:358
DEBUGTRACE
#define DEBUGTRACE(EXPR)
Definition: DebugTrace.hpp:119
gnsstk::GLOCNavHeader::preamble
uint32_t preamble
20 bit preamble for the message.
Definition: GLOCNavHeader.hpp:79
gnsstk::gloc::anbDeltaT
@ anbDeltaT
Definition: GLOCBits.hpp:354
gnsstk::GLOCNavHeader::TS
uint16_t TS
Time stamp (3 second counter for each string).
Definition: GLOCNavHeader.hpp:80
gnsstk::gloc::iscB2
@ iscB2
Definition: GLOCBits.hpp:407
gnsstk::GLOCNavAlm::deltaT
double deltaT
Draconic orbital period offset.
Definition: GLOCNavAlm.hpp:142
gnsstk::gloc::enbtauj
@ enbtauj
Definition: GLOCBits.hpp:187
gnsstk::gloc::esbtaucdot
@ esbtaucdot
Definition: GLOCBits.hpp:206
gnsstk::Exception::what
std::string what() const
Dump to a string.
Definition: Exception.cpp:193
gnsstk::gloc::enbDeltayjpc
@ enbDeltayjpc
Definition: GLOCBits.hpp:274
gnsstk::GLOCNavUT1TimeOffset::B0
double B0
Time bias in seconds.
Definition: GLOCNavUT1TimeOffset.hpp:103
gnsstk::gloc::esiRjE
@ esiRjE
Definition: GLOCBits.hpp:165
gnsstk::gloc::lsbax2
@ lsbax2
Definition: GLOCBits.hpp:462
GLOCNavIono.hpp
gnsstk::SatID
Definition: SatID.hpp:89
gnsstk::NavMessageType::Health
@ Health
SV health status information message.
gnsstk::NavDataPtrList
std::list< NavDataPtr > NavDataPtrList
Definition: NavData.hpp:75
gnsstk::GLOCNavEph::apcOffset
Triple apcOffset
L3OC APC offset from center of mass.
Definition: GLOCNavEph.hpp:158
gnsstk::gloc::esiDeltaxjpc
@ esiDeltaxjpc
Definition: GLOCBits.hpp:267
gnsstk::GLOCNavHeader
Definition: GLOCNavHeader.hpp:52
gnsstk::gloc::esczj
@ esczj
Definition: GLOCBits.hpp:229
gnsstk::gloc::esczjp
@ esczjp
Definition: GLOCBits.hpp:250
gnsstk::gloc::esbDeltaxjpc
@ esbDeltaxjpc
Definition: GLOCBits.hpp:268
gnsstk::gloc::lscax4
@ lscax4
Definition: GLOCBits.hpp:488
gnsstk::gloc::escTauGPS
@ escTauGPS
Definition: GLOCBits.hpp:290
gnsstk::gloc::isccA
@ isccA
Definition: GLOCBits.hpp:411
gnsstk::CommonTime::setTimeSystem
CommonTime & setTimeSystem(TimeSystem timeSystem)
Definition: CommonTime.hpp:195
gnsstk::gloc::enbDeltataujL3
@ enbDeltataujL3
Definition: GLOCBits.hpp:284
gnsstk::gloc::esbPS
@ esbPS
Definition: GLOCBits.hpp:146
gnsstk::GLOCNavAlm::tLambda
double tLambda
Instant in Moscow time when passing lambda.
Definition: GLOCNavAlm.hpp:138
gnsstk::gloc::inbB2
@ inbB2
Definition: GLOCBits.hpp:406
gnsstk::gloc::esiDeltayjpc
@ esiDeltayjpc
Definition: GLOCBits.hpp:272
gnsstk::PNBNavDataFactory::processTim
bool processTim
If true, time offset data will be output by addData.
Definition: PNBNavDataFactory.hpp:130
gnsstk::gloc::lscday0
@ lscday0
Definition: GLOCBits.hpp:444
gnsstk::gloc::lsbay2
@ lsbay2
Definition: GLOCBits.hpp:466
gnsstk::gloc::esiFjT
@ esiFjT
Definition: GLOCBits.hpp:180
gnsstk::gloc::lscdax0
@ lscdax0
Definition: GLOCBits.hpp:440
gnsstk::gloc::esiyjp
@ esiyjp
Definition: GLOCBits.hpp:236
gnsstk::PNBGLOCNavDataFactory::almAcc
std::map< NavSatelliteID, std::vector< PackedNavBitsPtr > > almAcc
Definition: PNBGLOCNavDataFactory.hpp:180
gnsstk::gloc::escEjT
@ escEjT
Definition: GLOCBits.hpp:163
gnsstk::PNBGLOCNavDataFactory::processHealth
bool processHealth(const PackedNavBitsPtr &navIn, NavDataPtrList &navOut)
Definition: PNBGLOCNavDataFactory.cpp:244
gnsstk::GLOCNavAlm::statusReg
unsigned statusReg
Status register (SRA 5.3.2.7).
Definition: GLOCNavAlm.hpp:134
gnsstk::NavData::signal
NavMessageID signal
Source signal identification for this navigation message data.
Definition: NavData.hpp:175
gnsstk::GLOCNavAlm::aoa
unsigned aoa
Age of almanac (EA).
Definition: GLOCNavAlm.hpp:132
gnsstk::gloc::fnbj
@ fnbj
Definition: GLOCBits.hpp:90
GLOCNavEph.hpp
gnsstk::gloc::esbyjpp
@ esbyjpp
Definition: GLOCBits.hpp:258
gnsstk::PNBNavDataFactory::processAlm
bool processAlm
If true, almanac data will be output by addData.
Definition: PNBNavDataFactory.hpp:126
gnsstk::gloc::asbDeltaT
@ asbDeltaT
Definition: GLOCBits.hpp:353
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::gloc::esiEjT
@ esiEjT
Definition: GLOCBits.hpp:160
gnsstk::gloc::asbDeltai
@ asbDeltai
Definition: GLOCBits.hpp:341
gnsstk::gloc::esbzjp
@ esbzjp
Definition: GLOCBits.hpp:248
PNBGLOCNavDataFactory.hpp
gnsstk::gloc::esbDeltazjpc
@ esbDeltazjpc
Definition: GLOCBits.hpp:278
gnsstk::gloc::esbBetaj
@ esbBetaj
Definition: GLOCBits.hpp:196
gnsstk::gloc::enbMj
@ enbMj
Definition: GLOCBits.hpp:142
gnsstk::gloc::esbMj
@ esbMj
Definition: GLOCBits.hpp:141
gnsstk::PNBGLOCNavDataFactory::TimeMeta::N4
vuint N4
Leap years since 1996.
Definition: PNBGLOCNavDataFactory.hpp:165
gnsstk::gloc::isbNB
@ isbNB
Definition: GLOCBits.hpp:369
gnsstk::gloc::inbcF107
@ inbcF107
Definition: GLOCBits.hpp:414
gnsstk::GLOCNavEph::freqBias
double freqBias
Satellite relative frequency bias (gamma^j).
Definition: GLOCNavEph.hpp:148
gnsstk::GLOCNavLTDMP::dax0
double dax0
Definition: GLOCNavLTDMP.hpp:85
gnsstk::GLOCNavLTDMP::ay4
double ay4
Definition: GLOCNavLTDMP.hpp:98
gnsstk::NavData::timeStamp
CommonTime timeStamp
Definition: NavData.hpp:173
gnsstk::PNBGLOCNavDataFactory::processLTDMP
bool processLTDMP(unsigned long stringID, const PackedNavBitsPtr &navIn)
Definition: PNBGLOCNavDataFactory.cpp:505
GLOCNavAlm.hpp
gnsstk::GLOCNavEph::header11
GLOCNavHeader header11
Header (incl xmit time) data from string 11.
Definition: GLOCNavEph.hpp:163
gnsstk::PNBNavDataFactory::processISC
bool processISC
If true, inter-signal correction data will be output by addData.
Definition: PNBNavDataFactory.hpp:134
gnsstk::gloc::enbyjpp
@ enbyjpp
Definition: GLOCBits.hpp:259
gnsstk::galfnav::fscType
@ fscType
page type scale factor
Definition: GalFBits.hpp:54
gnsstk::Exception
Definition: Exception.hpp:151
gnsstk::gloc::esbNT
@ esbNT
Definition: GLOCBits.hpp:136
gnsstk::GLOCNavLTDMP::az4
double az4
Definition: GLOCNavLTDMP.hpp:99
gnsstk::GLONASSTime
Definition: GLONASSTime.hpp:59
gnsstk::gloc::asbDeltaTdot
@ asbDeltaTdot
Definition: GLOCBits.hpp:357
gnsstk::GLOCNavAlm::satType
GLOCSatType satType
What satellite j is and what it transmits.
Definition: GLOCNavAlm.hpp:135
gnsstk::GLOCNavLTDMP::ax3
double ax3
Definition: GLOCNavLTDMP.hpp:94
gnsstk::gloc::escyjp
@ escyjp
Definition: GLOCBits.hpp:239
gnsstk::GLOCSatType
GLOCSatType
Values for Word M in the ephemeris (immediate) and almanac data.
Definition: GLOCSatType.hpp:47
gnsstk::gloc::esizjp
@ esizjp
Definition: GLOCBits.hpp:247
gnsstk::GLOCNavAlm::deltai
double deltai
Inclination offset from 64.8 degrees (semicirc).
Definition: GLOCNavAlm.hpp:139
gnsstk::gloc::esixj
@ esixj
Definition: GLOCBits.hpp:216
gnsstk::gloc::anbepsilon
@ anbepsilon
Definition: GLOCBits.hpp:346
gnsstk::gloc::isbcA
@ isbcA
Definition: GLOCBits.hpp:409
gnsstk::GLOCNavHeader::A
bool A
true=time correction planned (see ICD 4.2.2.10).
Definition: GLOCNavHeader.hpp:93
gnsstk::gloc::esiPS
@ esiPS
Definition: GLOCBits.hpp:145
gnsstk::gloc::esizjpp
@ esizjpp
Definition: GLOCBits.hpp:262
gnsstk::gloc::iscNB
@ iscNB
Definition: GLOCBits.hpp:371
gnsstk::gloc::esbEjE
@ esbEjE
Definition: GLOCBits.hpp:156
gnsstk::gloc::esbyjp
@ esbyjp
Definition: GLOCBits.hpp:237
gnsstk::gloc::lscaz1
@ lscaz1
Definition: GLOCBits.hpp:460
gnsstk::SVHealth::Healthy
@ Healthy
Satellite is in a healthy and useable state.
gnsstk::gloc::lscay3
@ lscay3
Definition: GLOCBits.hpp:480
gnsstk::GLOCNavUT1TimeOffset::B2
double B2
Time drift rate in s/s**2.
Definition: GLOCNavUT1TimeOffset.hpp:105
gnsstk::gloc::esiDeltataujL3
@ esiDeltataujL3
Definition: GLOCBits.hpp:282
gnsstk::GLOCNavAlm
Definition: GLOCNavAlm.hpp:61
gnsstk::GLOCNavEph::taucdot
double taucdot
Rate of correction for GLONASS to Moscow time.
Definition: GLOCNavEph.hpp:151
gnsstk::gloc::esbDeltayjpc
@ esbDeltayjpc
Definition: GLOCBits.hpp:273
gnsstk::GLOCNavLTDMP::tb32
unsigned long tb32
Reference instant in Moscow time for string 32.
Definition: GLOCNavLTDMP.hpp:81
gnsstk::NavType::GloCivilC
@ GloCivilC
gnsstk::gloc::lsbaz3
@ lsbaz3
Definition: GLOCBits.hpp:482
gnsstk::PNBGLOCNavDataFactory::timeAcc
std::map< NavSatelliteID, TimeMeta > timeAcc
Definition: PNBGLOCNavDataFactory.hpp:169
gnsstk::GLOCNavUT1TimeOffset::NB
unsigned NB
Day since the most recent leap year-aligned 4 years.
Definition: GLOCNavUT1TimeOffset.hpp:102
gnsstk::gloc::esiDeltazjpc
@ esiDeltazjpc
Definition: GLOCBits.hpp:277
gnsstk::gloc::asbNS
@ asbNS
Number of SVs in almanac.
Definition: GLOCBits.hpp:309
gnsstk::gloc::enbtauc
@ enbtauc
Definition: GLOCBits.hpp:202
gnsstk::gloc::escxjpp
@ escxjpp
Definition: GLOCBits.hpp:255
gnsstk::galfnav::fnbType
@ fnbType
page type number of bits
Definition: GalFBits.hpp:53
gnsstk::GLOCNavEph::fixFit
void fixFit()
Definition: GLOCNavEph.cpp:233
gnsstk::gloc::lscdaz0
@ lscdaz0
Definition: GLOCBits.hpp:448
gnsstk::PNBNavDataFactory::processEph
bool processEph
If true, ephemeris data will be output by addData.
Definition: PNBNavDataFactory.hpp:124
gnsstk::gloc::escxj
@ escxj
Definition: GLOCBits.hpp:219
gnsstk::gloc::isbB2
@ isbB2
Definition: GLOCBits.hpp:405
gnsstk::NavValidityType::InvalidOnly
@ InvalidOnly
Only load/find nav messages that fail validity checks.
gnsstk::gloc::escBetaj
@ escBetaj
Definition: GLOCBits.hpp:198
gnsstk::gloc::esiBetaj
@ esiBetaj
Definition: GLOCBits.hpp:195
gnsstk::gloc::escDeltaxjpc
@ escDeltaxjpc
Definition: GLOCBits.hpp:270
gnsstk::gloc::lscaz3
@ lscaz3
Definition: GLOCBits.hpp:484
gnsstk::GLOCNavAlm::ecc
double ecc
Eccentricity at tlambdaA.
Definition: GLOCNavAlm.hpp:140
gnsstk::gloc::esigammaj
@ esigammaj
Definition: GLOCBits.hpp:190
gnsstk::GLOCNavEph::clkBias
double clkBias
Satellite clock bias in sec (tau^j).
Definition: GLOCNavEph.hpp:147
gnsstk::gloc::enbtb
@ enbtb
Definition: GLOCBits.hpp:152
gnsstk::gloc::esitaucdot
@ esitaucdot
Definition: GLOCBits.hpp:205
gnsstk::gloc::asbtlambda
@ asbtlambda
Definition: GLOCBits.hpp:337
gnsstk::gloc::esiyjpp
@ esiyjpp
Definition: GLOCBits.hpp:257
gnsstk::NavValidityType::ValidOnly
@ ValidOnly
Only load/find nav messages that pass validity checks.
gnsstk::gloc::esbTauGPS
@ esbTauGPS
Definition: GLOCBits.hpp:288
gnsstk::GLOCNavEph::tauGPS
double tauGPS
Fractional part of offset from GPS to GLONASS time.
Definition: GLOCNavEph.hpp:160
gnsstk::gloc::lnbaz2
@ lnbaz2
Definition: GLOCBits.hpp:471
gnsstk::GLOCNavIono::solarIndex
double solarIndex
Solar activity index value (c_F10.7).
Definition: GLOCNavIono.hpp:83
gnsstk::gloc::enbDeltazjpc
@ enbDeltazjpc
Definition: GLOCBits.hpp:279
gnsstk::gloc::esbzj
@ esbzj
Definition: GLOCBits.hpp:227
gnsstk::gloc::fscP1
@ fscP1
Definition: GLOCBits.hpp:103
gnsstk::gloc::escDeltayjpc
@ escDeltayjpc
Definition: GLOCBits.hpp:275
gnsstk::gloc::str11
@ str11
Definition: GLOCBits.hpp:55
gnsstk::gloc::escRjT
@ escRjT
Definition: GLOCBits.hpp:173
gnsstk::gloc::esbEjT
@ esbEjT
Definition: GLOCBits.hpp:161
gnsstk::GLOCNavIono::peakTECF2
double peakTECF2
Factor of peak TEC of F2 layer (c_A).
Definition: GLOCNavIono.hpp:82
gnsstk::gloc::lnbax2
@ lnbax2
Definition: GLOCBits.hpp:463
GLOCBits.hpp
gnsstk::NavMessageType::Iono
@ Iono
Ionospheric correction data.
gnsstk::GLOCNavHeader::P1
uint8_t P1
SV call to ground control.
Definition: GLOCNavHeader.hpp:90
gnsstk::gloc::escFjE
@ escFjE
Definition: GLOCBits.hpp:178
gnsstk::gloc::lscaz4
@ lscaz4
Definition: GLOCBits.hpp:496
gnsstk::NavSatelliteID::sat
SatID sat
ID of satellite to which the nav data applies.
Definition: NavSatelliteID.hpp:169
gnsstk::gloc::firstEphString
@ firstEphString
Definition: GLOCBits.hpp:53
gnsstk::gloc::lsbdax0
@ lsbdax0
Definition: GLOCBits.hpp:438
gnsstk::gloc::str10
@ str10
Definition: GLOCBits.hpp:54
gnsstk::PNBGLOCNavDataFactory::processEarth
bool processEarth(const PackedNavBitsPtr &navIn, NavDataPtrList &navOut)
Definition: PNBGLOCNavDataFactory.cpp:202
gnsstk::gloc::anbNA
@ anbNA
Definition: GLOCBits.hpp:318
gnsstk::gloc::enbPS
@ enbPS
Definition: GLOCBits.hpp:147
gnsstk::GLOCNavEph::tauc
double tauc
Correction for GLONASS to Moscow time.
Definition: GLOCNavEph.hpp:150
gnsstk::gloc::lsbax1
@ lsbax1
Definition: GLOCBits.hpp:450
gnsstk::gloc::lsbdaz0
@ lsbdaz0
Definition: GLOCBits.hpp:446
gnsstk::gloc::escFjT
@ escFjT
Definition: GLOCBits.hpp:183
gnsstk::CommonTime
Definition: CommonTime.hpp:84
gnsstk::gloc::fscPreamble
@ fscPreamble
Definition: GLOCBits.hpp:78
gnsstk::PNBGLOCNavDataFactory::addData
bool addData(const PackedNavBitsPtr &navIn, NavDataPtrList &navOut, double cadence=-1) override
Definition: PNBGLOCNavDataFactory.cpp:71
gnsstk::GLOCNavLTDMP::ay3
double ay3
Definition: GLOCNavLTDMP.hpp:95
gnsstk::GLOCNavLTDMP::daz0
double daz0
Definition: GLOCNavLTDMP.hpp:87
gnsstk::gloc::inbB1
@ inbB1
Definition: GLOCBits.hpp:402
gnsstk::gloc
Definition: GLOCBits.hpp:44
gnsstk::gloc::anbSR
@ anbSR
Definition: GLOCBits.hpp:322
gnsstk::gloc::lscax1
@ lscax1
Definition: GLOCBits.hpp:452
gnsstk::GLOCNavLTDMP::ax1
double ax1
Definition: GLOCNavLTDMP.hpp:88
gnsstk::gloc::fsbPreamble
@ fsbPreamble
Preamble start bit.
Definition: GLOCBits.hpp:76
gnsstk::GLOCNavEph::FjE
int8_t FjE
Accuracy factors dependent on ephemeris errors.
Definition: GLOCNavEph.hpp:145
gnsstk::gloc::fsbA
@ fsbA
Time corr planned start bit.
Definition: GLOCBits.hpp:113
gnsstk::GLOCNavAlm::fixFit
void fixFit()
Definition: GLOCNavAlm.cpp:110
gnsstk::GLOCNavAlm::tau
double tau
Time correction from L3OCd to GLONASS.
Definition: GLOCNavAlm.hpp:136
gnsstk::GLOCRegime
GLOCRegime
Regime for data generation (RjE, RjT, see ICD 5.2.2.8).
Definition: GLOCRegime.hpp:47
gnsstk::gloc::enbzjp
@ enbzjp
Definition: GLOCBits.hpp:249
gnsstk::gloc::escgammaj
@ escgammaj
Definition: GLOCBits.hpp:193
example6.valid
valid
Definition: example6.py:20
gnsstk::GLOCNavLTDMP::header31
GLOCNavHeader header31
Header (incl xmit time) data from string 31.
Definition: GLOCNavLTDMP.hpp:78
gnsstk::GLOCNavAlm::Toa
CommonTime Toa
Reference time for almanac.
Definition: GLOCNavAlm.hpp:129
CivilTime.hpp
gnsstk::gloc::ascTO
@ ascTO
Definition: GLOCBits.hpp:307
gnsstk::gloc::fnbP1
@ fnbP1
Definition: GLOCBits.hpp:102
gnsstk::gloc::esiMj
@ esiMj
Definition: GLOCBits.hpp:140
gnsstk::gloc::enbTauGPS
@ enbTauGPS
Definition: GLOCBits.hpp:289
gnsstk::galfnav::fsbType
@ fsbType
page type start bit
Definition: GalFBits.hpp:52
gnsstk::gloc::asctlambda
@ asctlambda
Definition: GLOCBits.hpp:339
gnsstk::gloc::anblambda
@ anblambda
Definition: GLOCBits.hpp:334
gnsstk::gloc::ascDeltaTdot
@ ascDeltaTdot
Definition: GLOCBits.hpp:359
gnsstk::gloc::isbB0
@ isbB0
Definition: GLOCBits.hpp:397
gnsstk::gloc::esixjp
@ esixjp
Definition: GLOCBits.hpp:231
gnsstk::GLOCNavEph::FjT
int8_t FjT
Accuracy factors dependent on clock errors.
Definition: GLOCNavEph.hpp:146
gnsstk::gloc::enbN4
@ enbN4
Definition: GLOCBits.hpp:132
gnsstk::gloc::lscay4
@ lscay4
Definition: GLOCBits.hpp:492
gnsstk::gloc::escyj
@ escyj
Definition: GLOCBits.hpp:224
gnsstk::TimeSystem::GLO
@ GLO
GLONASS system time (aka UTC(SU))
gnsstk::gloc::fsbj
@ fsbj
SV ID start bit.
Definition: GLOCBits.hpp:89
gnsstk::gloc::lnbay1
@ lnbay1
Definition: GLOCBits.hpp:455
gnsstk::GLOCNavHeader::health
SVHealth health
SV health status.
Definition: GLOCNavHeader.hpp:89
gnsstk::gloc::escEjE
@ escEjE
Definition: GLOCBits.hpp:158
gnsstk::gloc::asbSR
@ asbSR
Status register.
Definition: GLOCBits.hpp:321
gnsstk::gloc::isbcAp
@ isbcAp
Definition: GLOCBits.hpp:417
gnsstk::gloc::esiN4
@ esiN4
Definition: GLOCBits.hpp:130
GLONASSTime.hpp
gnsstk::gloc::enbxj
@ enbxj
Definition: GLOCBits.hpp:218
gnsstk::GLOCNavLTDMP::az2
double az2
Definition: GLOCNavLTDMP.hpp:93
gnsstk::gloc::enbDeltaxjpc
@ enbDeltaxjpc
Definition: GLOCBits.hpp:269
gnsstk::GLOCNavLTDMP::ay1
double ay1
Definition: GLOCNavLTDMP.hpp:89
gnsstk::gloc::lsbaz2
@ lsbaz2
Definition: GLOCBits.hpp:470
gnsstk::GLOCNavLTDMP::az3
double az3
Definition: GLOCNavLTDMP.hpp:96
gnsstk::NavMessageType::TimeOffset
@ TimeOffset
Message containing information about time system offsets.
gnsstk::GLOCNavEph::N4
uint8_t N4
Number of leap years since 1996.
Definition: GLOCNavEph.hpp:136
gnsstk::gloc::fsbTS
@ fsbTS
Time Stamp start bit.
Definition: GLOCBits.hpp:85
gnsstk::gloc::enbRjT
@ enbRjT
Definition: GLOCBits.hpp:172
gnsstk::GLOCNavHeader::svUnhealthy
bool svUnhealthy
Health flag (Hj, false=healthy).
Definition: GLOCNavHeader.hpp:87
gnsstk::gloc::ascDeltai
@ ascDeltai
Definition: GLOCBits.hpp:343
gnsstk::gloc::anbtau
@ anbtau
Definition: GLOCBits.hpp:330
gnsstk::PNBNavDataFactory::processHea
bool processHea
If true, health data will be output by addData.
Definition: PNBNavDataFactory.hpp:128
gnsstk::GLOCNavUT1TimeOffset::UTCTAI
double UTCTAI
Leap seconds - not really used.
Definition: GLOCNavUT1TimeOffset.hpp:106
gnsstk::gloc::lnbax4
@ lnbax4
Definition: GLOCBits.hpp:487
gnsstk::gloc::esbtauc
@ esbtauc
Definition: GLOCBits.hpp:201
gnsstk::gloc::esiFjE
@ esiFjE
Definition: GLOCBits.hpp:175
DebugTrace.hpp
gnsstk::gloc::lnbaz3
@ lnbaz3
Definition: GLOCBits.hpp:483
gnsstk::gloc::asbNA
@ asbNA
Days from leap year.
Definition: GLOCBits.hpp:317
std
Definition: Angle.hpp:142
gnsstk::gloc::esbRjE
@ esbRjE
Definition: GLOCBits.hpp:166
gnsstk::GLOCNavLTDMP::ax4
double ax4
Definition: GLOCNavLTDMP.hpp:97
gnsstk::gloc::esbDeltataujL3
@ esbDeltataujL3
Definition: GLOCBits.hpp:283
gnsstk::PNBGLOCNavDataFactory::processHeader
bool processHeader(const PackedNavBitsPtr &navIn, GLOCNavHeader &navOut)
Definition: PNBGLOCNavDataFactory.cpp:175
gnsstk::gloc::isccAp
@ isccAp
Definition: GLOCBits.hpp:419
gnsstk::gloc::escN4
@ escN4
Definition: GLOCBits.hpp:133
gnsstk::NavMessageType::Ephemeris
@ Ephemeris
Precision orbits for the transmitting SV.
gnsstk::gloc::fsbHj
@ fsbHj
SV health start bit.
Definition: GLOCBits.hpp:93
gnsstk::GLOCNavLTDMP
Definition: GLOCNavLTDMP.hpp:55
GLOCNavHealth.hpp
gnsstk::gloc::ascomega
@ ascomega
Definition: GLOCBits.hpp:351
gnsstk::gloc::asblambda
@ asblambda
Definition: GLOCBits.hpp:333
gnsstk::gloc::esbRjT
@ esbRjT
Definition: GLOCBits.hpp:171
gnsstk::gloc::lnbtb
@ lnbtb
Definition: GLOCBits.hpp:435
gnsstk::gloc::fscTS
@ fscTS
Definition: GLOCBits.hpp:87
gnsstk::GLOCNavEph::ltdmp
GLOCNavLTDMP ltdmp
Long-term dynamic model parameters.
Definition: GLOCNavEph.hpp:161
gnsstk::gloc::lnbay4
@ lnbay4
Definition: GLOCBits.hpp:491
gnsstk::GLOCNavHeader::KP
unsigned KP
Leap second indicator (see ICD 4.2.2.9).
Definition: GLOCNavHeader.hpp:92
gnsstk::gloc::enbxjp
@ enbxjp
Definition: GLOCBits.hpp:233
gnsstk::GLOCNavAlm::omega
double omega
Almanac parameter for argument of perigee (semicirc).
Definition: GLOCNavAlm.hpp:141
gnsstk::gloc::asctau
@ asctau
Definition: GLOCBits.hpp:331
gnsstk::gloc::lsbday0
@ lsbday0
Definition: GLOCBits.hpp:442
gnsstk::GLOCNavAlm::lambda
double lambda
Longitude of first ascending node (semicirc).
Definition: GLOCNavAlm.hpp:137
gnsstk::GLOCNavEph::NT
uint16_t NT
Day within four-year interval N4.
Definition: GLOCNavEph.hpp:137
gnsstk::gloc::esctaucdot
@ esctaucdot
Definition: GLOCBits.hpp:208
gnsstk::gloc::enbgammaj
@ enbgammaj
Definition: GLOCBits.hpp:192
gnsstk::GLOCNavEph::driftRate
double driftRate
Half rate of relative deviation of carrier freq.
Definition: GLOCNavEph.hpp:149
gnsstk::gloc::enbtaucdot
@ enbtaucdot
Definition: GLOCBits.hpp:207
gnsstk::GLOCNavHeader::xmit
CommonTime xmit
Transmit time of the string.
Definition: GLOCNavHeader.hpp:78
gnsstk::gloc::anbomega
@ anbomega
Definition: GLOCBits.hpp:350
gnsstk::gloc::isccF107
@ isccF107
Definition: GLOCBits.hpp:415
gnsstk::gloc::esbFjE
@ esbFjE
Definition: GLOCBits.hpp:176
DEBUGTRACE_FUNCTION
#define DEBUGTRACE_FUNCTION()
Definition: DebugTrace.hpp:117
gnsstk::gloc::esbxjp
@ esbxjp
Definition: GLOCBits.hpp:232
gnsstk::gloc::escxjp
@ escxjp
Definition: GLOCBits.hpp:234
gnsstk::gloc::esitauc
@ esitauc
Definition: GLOCBits.hpp:200
gnsstk::gloc::lscay1
@ lscay1
Definition: GLOCBits.hpp:456
gnsstk::gloc::asbepsilon
@ asbepsilon
Definition: GLOCBits.hpp:345
gnsstk::GLOCNavHeader::P2
bool P2
false=sun pointing (see ICD 4.2.2.8).
Definition: GLOCNavHeader.hpp:91
gnsstk::GLOCNavLTDMP::az1
double az1
Definition: GLOCNavLTDMP.hpp:90
gnsstk::gloc::lnbay2
@ lnbay2
Definition: GLOCBits.hpp:467
gnsstk::gloc::fnbKP
@ fnbKP
Definition: GLOCBits.hpp:110
gnsstk::GLOCNavAlm::deltaTdot
double deltaTdot
Draconic orbital period rate.
Definition: GLOCNavAlm.hpp:143
gnsstk::gloc::ascE
@ ascE
Definition: GLOCBits.hpp:315
gnsstk::gloc::lsbay3
@ lsbay3
Definition: GLOCBits.hpp:478
gnsstk::gloc::fnbPreamble
@ fnbPreamble
Definition: GLOCBits.hpp:77
gnsstk::gloc::escDeltataujL3
@ escDeltataujL3
Definition: GLOCBits.hpp:285
gnsstk::gloc::esbgammaj
@ esbgammaj
Definition: GLOCBits.hpp:191
gnsstk::gloc::enbRjE
@ enbRjE
Definition: GLOCBits.hpp:167
gnsstk::PNBGLOCNavDataFactory::ltdmpAcc
std::map< NavSatelliteID, GLOCNavLTDMP > ltdmpAcc
Definition: PNBGLOCNavDataFactory.hpp:176
gnsstk::gloc::esiyj
@ esiyj
Definition: GLOCBits.hpp:221
gnsstk::gloc::esbN4
@ esbN4
Definition: GLOCBits.hpp:131
gnsstk::gloc::asbTO
@ asbTO
Orbit type.
Definition: GLOCBits.hpp:305
gnsstk::gloc::fscj
@ fscj
Definition: GLOCBits.hpp:91
gnsstk::gloc::asbE
@ asbE
Age of almanac.
Definition: GLOCBits.hpp:313
gnsstk::GLOCNavLTDMP::ax2
double ax2
Definition: GLOCNavLTDMP.hpp:91
gnsstk::GLOCNavAlm::NA
unsigned NA
Almanac reference time days since leap year.
Definition: GLOCNavAlm.hpp:133
gnsstk::gloc::enbzjpp
@ enbzjpp
Definition: GLOCBits.hpp:264
gnsstk::gloc::enbxjpp
@ enbxjpp
Definition: GLOCBits.hpp:254
gnsstk::gloc::esctauj
@ esctauj
Definition: GLOCBits.hpp:188
gnsstk::gloc::esbtauj
@ esbtauj
Definition: GLOCBits.hpp:186
gnsstk::GLOCNavLTDMP::ay2
double ay2
Definition: GLOCNavLTDMP.hpp:92
GLOCNavUT1TimeOffset.hpp
gnsstk::gloc::anbtlambda
@ anbtlambda
Definition: GLOCBits.hpp:338
gnsstk::gloc::ascM
@ ascM
Definition: GLOCBits.hpp:327
gnsstk::gloc::esiRjT
@ esiRjT
Definition: GLOCBits.hpp:170
gnsstk::SVHealth::Unhealthy
@ Unhealthy
Satellite is unhealthy and should not be used.
gnsstk::gloc::fsblj
@ fsblj
data validity start bit
Definition: GLOCBits.hpp:97
gnsstk::gloc::esiTauGPS
@ esiTauGPS
Definition: GLOCBits.hpp:287
gnsstk::gloc::ascSR
@ ascSR
Definition: GLOCBits.hpp:323
gnsstk::gloc::fscKP
@ fscKP
Definition: GLOCBits.hpp:111
gnsstk::GLOCOrbitType
GLOCOrbitType
Values for Word TO in the almanac data.
Definition: GLOCOrbitType.hpp:47
gnsstk::GLOCNavEph::header12
GLOCNavHeader header12
Header (incl xmit time) data from string 12.
Definition: GLOCNavEph.hpp:164
gnsstk::gloc::asbomega
@ asbomega
Definition: GLOCBits.hpp:349
gnsstk::gloc::asclambda
@ asclambda
Definition: GLOCBits.hpp:335
gnsstk::gloc::enbNT
@ enbNT
Definition: GLOCBits.hpp:137
gnsstk::gloc::lsbax3
@ lsbax3
Definition: GLOCBits.hpp:474
gnsstk::gloc::ascDeltaT
@ ascDeltaT
Definition: GLOCBits.hpp:355
gnsstk::gloc::enbEjE
@ enbEjE
Definition: GLOCBits.hpp:157
gnsstk::gloc::anbE
@ anbE
Definition: GLOCBits.hpp:314
gnsstk::PNBGLOCNavDataFactory::TimeMeta::setN4
void setN4(unsigned v)
Set the value of N4 (from string 10).
Definition: PNBGLOCNavDataFactory.cpp:564
gnsstk::gloc::lsbay1
@ lsbay1
Definition: GLOCBits.hpp:454
gnsstk::gloc::esctb
@ esctb
Definition: GLOCBits.hpp:153
gnsstk::gloc::lnbdaz0
@ lnbdaz0
Definition: GLOCBits.hpp:447
gnsstk::GLOCNavUT1TimeOffset::refTime
CommonTime refTime
Reference time for computation.
Definition: GLOCNavUT1TimeOffset.hpp:101
gnsstk::GLOCNavEph::tb
unsigned long tb
Instant in Moscow time this data relates to.
Definition: GLOCNavEph.hpp:140
gnsstk::gloc::esixjpp
@ esixjpp
Definition: GLOCBits.hpp:252
gnsstk::gloc::esbtb
@ esbtb
Definition: GLOCBits.hpp:151
TimeString.hpp
gnsstk::gloc::lscaz2
@ lscaz2
Definition: GLOCBits.hpp:472
gnsstk::gloc::lscay2
@ lscay2
Definition: GLOCBits.hpp:468
gnsstk::gloc::esitauj
@ esitauj
Definition: GLOCBits.hpp:185
gnsstk::gloc::esbzjpp
@ esbzjpp
Definition: GLOCBits.hpp:263
gnsstk::NavMessageType::Almanac
@ Almanac
Low-precision orbits for other than the transmitting SV.
gnsstk::GLOCNavHealth
Definition: GLOCNavHealth.hpp:52
gnsstk::gloc::lnbaz1
@ lnbaz1
Definition: GLOCBits.hpp:459
gnsstk::gloc::isbUTCTAI
@ isbUTCTAI
Definition: GLOCBits.hpp:421
gnsstk::gloc::lnbax3
@ lnbax3
Definition: GLOCBits.hpp:475
gnsstk::gloc::esbyj
@ esbyj
Definition: GLOCBits.hpp:222
gnsstk::gloc::lsbtb
@ lsbtb
Definition: GLOCBits.hpp:434
gnsstk::gloc::escDeltazjpc
@ escDeltazjpc
Definition: GLOCBits.hpp:280
gnsstk::PNBNavDataFactory::processIono
bool processIono
If true, ionospheric data will be output by addData.
Definition: PNBNavDataFactory.hpp:132
gnsstk::PNBNavDataFactory::navValidity
NavValidityType navValidity
Determines how the factory should filter added data.
Definition: PNBNavDataFactory.hpp:121


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