SP3NavDataFactory.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 <iterator>
40 #include "SP3NavDataFactory.hpp"
41 #include "SP3Stream.hpp"
42 #include "SP3Header.hpp"
43 #include "SP3Data.hpp"
44 #include "OrbitDataSP3.hpp"
45 #include "Rinex3ClockStream.hpp"
46 #include "Rinex3ClockHeader.hpp"
47 #include "Rinex3ClockData.hpp"
48 #include "TimeString.hpp"
49 #include "MiscMath.hpp"
50 #include "DebugTrace.hpp"
52 
53 using namespace std;
54 
56 static const std::string dts("%Y/%02m/%02d %02H:%02M:%02S %3j %P");
57 
58 namespace gnsstk
59 {
60  const ObsID SP3NavDataFactory::oidGPS(ObservationType::NavMsg,
61  CarrierBand::L1,TrackingCode::CA,0,0);
62  const ObsID SP3NavDataFactory::oidGalileo(ObservationType::NavMsg,
63  CarrierBand::L5,
64  TrackingCode::E5aI,0,0);
65  const ObsID SP3NavDataFactory::oidQZSS(ObservationType::NavMsg,
66  CarrierBand::L1,TrackingCode::CA,0,0);
67  const ObsID SP3NavDataFactory::oidGLONASS(ObservationType::NavMsg,
68  CarrierBand::G1,
69  TrackingCode::Standard);
70  const ObsID SP3NavDataFactory::oidBeiDou(ObservationType::NavMsg,
71  CarrierBand::B1,TrackingCode::B1I,
72  0,0);
73  const NavType SP3NavDataFactory::ntGPS(NavType::GPSLNAV);
74  const NavType SP3NavDataFactory::ntGalileo(NavType::GalFNAV);
75  const NavType SP3NavDataFactory::ntQZSS(NavType::GPSLNAV);
76  const NavType SP3NavDataFactory::ntGLONASS(NavType::GloCivilF);
77  const NavType SP3NavDataFactory::ntBeiDou(NavType::BeiDou_D1);
78 
80  const double maxBias = 999999.0;
81 
82  SP3NavDataFactory ::
83  SP3NavDataFactory()
84  : storeTimeSystem(TimeSystem::Any),
85  checkDataGapPos(false),
86  gapIntervalPos(0.0),
87  checkDataGapClk(false),
88  gapIntervalClk(0.0),
89  checkIntervalPos(false),
90  maxIntervalPos(0.0),
91  checkIntervalClk(false),
92  maxIntervalClk(0.0),
93  useSP3clock(true),
94  rejectBadPosFlag(true),
95  rejectBadClockFlag(true),
96  rejectPredPosFlag(false),
97  rejectPredClockFlag(false),
98  interpType(ClkInterpType::Lagrange),
99  halfOrderClk(5),
100  halfOrderPos(5)
101  {
161  NavType::GPSMNAV, 0, 0));
165  NavType::GPSMNAV, 0, 0));
169  NavType::GPSMNAV, 0, 0));
173  NavType::GPSMNAV, 0, 0));
177  NavType::GPSMNAV, 0, 0));
181  NavType::GPSMNAV, 0, 0));
185  NavType::GPSMNAV, 0, 0));
189  NavType::GPSMNAV, 0, 0));
193  NavType::GPSMNAV, 0, 0));
197  NavType::GPSMNAV, 0, 0));
234  }
235 
236 
238  find(const NavMessageID& nmid, const CommonTime& when,
239  NavDataPtr& navOut, SVHealth xmitHealth, NavValidityType valid,
240  NavSearchOrder order)
241  {
243  bool rv;
244  NavMessageID genericID;
246  {
247  return false;
248  }
249  // ignore the return code of transNavMsgID, find might still work.
250  transNavMsgID(nmid, genericID);
251  rv = findGeneric(NavMessageType::Ephemeris, genericID, when, navOut);
252  if (rv == false)
253  {
254  return false;
255  }
260  return findGeneric(NavMessageType::Clock, genericID, when, navOut);
261  }
262 
263 
264  // This method is roughly equivalent to the deprecated
265  // TabularSatStore::getTableInterval.
266  // Implementation notes:
267  // * iterator ti3 is used as an "end"-type quantity, meaning the
268  // interpolation methods will iterate from ti1 (inclusive) to
269  // ti3 (exclusive). This differs from the deprecated
270  // TabularSatStore which iterates from it1 to it2 inclusive.
273  const CommonTime& when, NavDataPtr& navData)
274  {
276  DEBUGTRACE("nmt=" << StringUtils::asString(nmt));
277  DEBUGTRACE("nsid=" << nsid);
278  DEBUGTRACE("when=" << printTime(when,dts));
279  unsigned halfOrder;
280  bool checkDataGap, checkInterval, findEph;
281  double gapInterval, maxInterval;
282  if (nmt == NavMessageType::Ephemeris)
283  {
284  findEph = true;
285  halfOrder = halfOrderPos;
286  checkDataGap = checkDataGapPos;
287  gapInterval = gapIntervalPos;
288  checkInterval = checkIntervalPos;
289  maxInterval = maxIntervalPos;
290  }
291  else if (nmt == NavMessageType::Clock)
292  {
293  findEph = false;
294  halfOrder = halfOrderClk;
295  checkDataGap = checkDataGapClk;
296  gapInterval = gapIntervalClk;
297  checkInterval = checkIntervalClk;
298  maxInterval = maxIntervalClk;
299  }
300  else
301  {
302  return false;
303  }
304  auto dataIt = data.find(nmt);
305  if (dataIt == data.end())
306  {
307  DEBUGTRACE("no data for nav message type");
308  return false;
309  }
310  if (!nsid.isWild())
311  {
312  auto sati = dataIt->second.find(nsid);
313  if (sati == dataIt->second.end())
314  {
315  DEBUGTRACE("no data!");
316  return false;
317  }
318  return findIterator(sati, when, navData, halfOrder, findEph,
319  checkDataGap, checkInterval, gapInterval,
320  maxInterval);
321  }
322  else
323  {
324  // To support wildcard signals, we need to do a linear search.
325  bool rv = false;
326  for (auto sati = dataIt->second.begin(); sati != dataIt->second.end();
327  sati++)
328  {
329  if (sati->first != nsid)
330  continue; // skip non matches
331  rv = findIterator(sati, when, navData, halfOrder, findEph,
332  checkDataGap, checkInterval, gapInterval,
333  maxInterval);
334  if (rv)
335  break;
336  }
337  return rv;
338  }
339  }
340 
341 
343  findIterator(NavSatMap::iterator& sati,
344  const CommonTime& when, NavDataPtr& navData,
345  unsigned halfOrder, bool findEph,
346  bool checkDataGap, bool checkInterval,
347  double gapInterval, double maxInterval)
348  {
349  bool giveUp = false;
350  // This is not the entry we want, but it is instead the first
351  // entry we probably (depending on order) *don't* want.
352  auto ti2 = sati->second.upper_bound(when);
353  auto ti1 = ti2, ti3 = ti2;
354  if (ti2 == sati->second.end())
355  {
356  // Since we're at the end we can't do interpolation,
357  // but we can still check for an exact match.
358  DEBUGTRACE("probably giving up because we're at the end");
359  giveUp = true;
360  }
361  else
362  {
363  DEBUGTRACE(printTime(ti2->first," ti2 has been set to "+dts));
364  // I wouldn't have done this except that I'm trying to
365  // match the behavior of SP3EphemerisStore. Basically,
366  // for exact matches, the interpolation interval is
367  // shifted "left" by one, but not when the time match
368  // is not exact.
369  auto tiTmp = std::prev(ti2);
370  unsigned offs = 0;
371  bool exactMatch = false;
372  if ((tiTmp != sati->second.end()) &&
373  (tiTmp->second->timeStamp == when))
374  {
375  exactMatch = true;
376  offs = 1;
377  }
379  {
380  CommonTime dt2(ti2->first);
382  DEBUGTRACE("gap = " << (dt2 - tiTmp->first));
383  }
384  if (checkDataGap && (tiTmp != sati->second.end()) &&
385  ((ti2->first - tiTmp->first) > gapInterval))
386  {
387  DEBUGTRACE("giving up because the gap interval is too big");
388  giveUp = true;
389  }
390 
391  // now expand the interval to include 2*halfOrder timesteps
392  // if possible.
395  // Check to see if we can do interpolation.
396  unsigned count = 0;
397  if (!giveUp)
398  {
399  while (true)
400  {
401  count++;
402  if (count > halfOrder+offs)
403  {
404  break;
405  }
406  if ((ti1 == sati->second.end()) ||
407  ((ti3 == sati->second.end()) &&
408  (count <= halfOrder-offs)) ||
409  ((ti1 == sati->second.begin()) &&
410  (count <= halfOrder+offs)))
411  {
412  // give up and reset the iterators to the starting point.
413  giveUp = true;
414  ti1 = ti3 = ti2;
415  break;
416  }
417  if (count <= halfOrder+offs)
418  {
419  --ti1;
420  }
421  if (count <= halfOrder-offs)
422  {
423  ++ti3;
424  }
425  }
426  }
427  }
428  // always back up one which allows us to check for exact match.
429  ti2 = std::prev(ti2);
430  if (ti2 == sati->second.end())
431  {
432  DEBUGTRACE("ti2 is now end?");
433  // Nothing available that's even close.
434  return false;
435  }
436  DEBUGTRACE(printTime(ti2->first," ti2 has been set to "+dts));
437  if (!giveUp)
438  {
439  // Need a copy of ti3 to move it back 1, as otherwise
440  // the interval check will give the wrong results since
441  // it's 1 beyond the actual last interpolated item.
442  auto iti3 = std::prev(ti3);
443  DEBUGTRACE("distance from ti1 to ti2 = " << std::distance(ti1,ti2));
444  DEBUGTRACE("distance from ti2 to ti3 = " << std::distance(ti2,ti3));
445  DEBUGTRACE("interval = " << (iti3->first - ti1->first));
446  if (checkInterval && ((iti3->first - ti1->first) > maxInterval))
447  {
448  DEBUGTRACE("giving up because the interpolation interval is too"
449  " big");
450  giveUp = true;
451  }
452  }
453  if (ti2->second->timeStamp == when)
454  {
455  // Even though it's an exact match, we still need to
456  // make a new object so that we can fill in clock
457  // information without affecting the internal store.
458  if (!navData)
459  {
460  OrbitDataSP3 *stored = dynamic_cast<OrbitDataSP3*>(
461  ti2->second.get());
462  navData = std::make_shared<OrbitDataSP3>(*stored);
463  // ti2->second->dump(std::cerr, DumpDetail::Full);
464  // navData->dump(std::cerr, DumpDetail::Full);
465  // If giveUp is not set, then we can do some
466  // interpolation to fill in any missing data.
467  if (!giveUp)
468  {
469  if (findEph)
470  {
471  DEBUGTRACE("interpolating ephemeris for exact match");
472  interpolateEph(ti1, ti3, when, navData);
473  }
474  else
475  {
476  DEBUGTRACE("interpolating clock for exact match");
477  interpolateClk(ti1, ti3, when, navData);
478  }
479  }
480  DEBUGTRACE("found an exact match");
481  return true;
482  }
483  else
484  {
485  OrbitDataSP3 *stored = dynamic_cast<OrbitDataSP3*>(
486  ti2->second.get());
487  OrbitDataSP3 *navOut = dynamic_cast<OrbitDataSP3*>(
488  navData.get());
489  if (findEph)
490  {
491  navOut->copyXV(*stored);
492  // fill in missing data if we can
493  if (!giveUp)
494  {
495  DEBUGTRACE("interpolating ephemeris for exact match (2)");
496  interpolateEph(ti1, ti3, when, navData);
497  }
498  }
499  else
500  {
501  navOut->copyT(*stored);
502  // fill in missing data if we can
503  if (!giveUp)
504  {
505  DEBUGTRACE("interpolating clock for exact match (2)");
506  interpolateClk(ti1, ti3, when, navData);
507  }
508  }
509  // stored->dump(std::cerr, DumpDetail::Full);
510  // navOut->dump(std::cerr, DumpDetail::Full);
511  DEBUGTRACE("found an exact match with existing data");
512  return true;
513  }
514  }
515  else if (giveUp)
516  {
517  // not an exact match and no data available for interpolation.
518  DEBUGTRACE("giving up, insufficient data for interpolation");
519  return false;
520  }
521  else
522  {
523  DEBUGTRACE("faking interpolation");
524  if (!navData)
525  {
526  DEBUGTRACE("creating new empty navData");
527  OrbitDataSP3 *stored = dynamic_cast<OrbitDataSP3*>(
528  ti2->second.get());
529  navData = std::make_shared<OrbitDataSP3>(*stored);
530  navData->timeStamp = when;
531  }
532  else
533  {
534  DEBUGTRACE("already have valid navData");
535  }
536  DEBUGTRACE("OK, have interval " << printTime(ti1->first,""+dts)
537  << " <= " <<printTime(when,""+dts)<< " < "
538  << printTime(ti3->first,dts));
539  if (findEph)
540  {
541  interpolateEph(ti1, ti3, when, navData);
542  return true;
543  }
544  else
545  {
546  interpolateClk(ti1, ti3, when, navData);
547  return true;
548  }
549  } // else (do interpolation)
550  DEBUGTRACE("giving up at the end");
551  return false;
552  }
553 
554 
556  addDataSource(const std::string& source)
557  {
560  offsetData);
561  return process(source, cb);
562  }
563 
564 
566  process(const std::string& filename,
568  {
570  bool rv = true;
571  bool processEph = (procNavTypes.count(NavMessageType::Ephemeris) > 0);
572  bool processClk = (procNavTypes.count(NavMessageType::Clock) > 0);
573  // When either of these two change, we store the existing
574  // NavDataPtr and create a new one.
575  CommonTime lastTime;
576  SatID lastSat;
577  NavDataPtr eph, clk;
578  try
579  {
580  SP3Stream is(filename.c_str(), ios::in);
581  SP3Header head;
582  SP3Data data;
583  if (!is)
584  {
585  return false;
586  }
587  is >> head;
588  if (!is)
589  {
590  return addRinexClock(filename, cb);
591  }
592 
593  // know whether to look for the extra info contained in SP3c
594  bool isC = (head.version==SP3Header::SP3c);
595  // check/save TimeSystem to storeTimeSystem
596  if ((head.timeSystem != TimeSystem::Any) &&
597  (head.timeSystem != TimeSystem::Unknown))
598  {
599  // if store time system has not been set, do so
601  {
603  storeTimeSystem = head.timeSystem;
604  }
605  else if (storeTimeSystem != head.timeSystem)
606  {
607  // Don't load an SP3 file with a differing time system
608  cerr << "Time system mismatch in SP3 data, "
610  << " (store) != "
611  << gnsstk::StringUtils::asString(head.timeSystem)
612  << " (file)" << endl;
613  return false;
614  }
615  }
616 
617  while (is)
618  {
619  is >> data;
620  if (!is)
621  {
622  if (is.eof())
623  break;
624  else
625  return false; // some other error
626  }
627  if ((lastSat != data.sat) || (lastTime != data.time))
628  {
629  DEBUGTRACE("time or satellite change, storing");
630  lastSat = data.sat;
631  lastTime = data.time;
632  DEBUGTRACE("storing eph");
633  if (!store(processEph, cb, eph))
634  return false;
635  DEBUGTRACE("storing clk");
636  if (!store(processClk && useSP3clock, cb, clk))
637  return false;
638  }
639  // Don't process time records otherwise we'll end up
640  // storing junk in the store that has a time stamp and
641  // a bogus satellite ID.
642  if (data.RecType != '*')
643  {
644  if (rejectBadPosFlag &&
645  (data.x[0] == 0.0) ||
646  (data.x[1] == 0.0) ||
647  (data.x[2] == 0.0))
648  {
649  // don't add this record with a bad position
650  continue;
651  }
652  else if (rejectBadClockFlag && (fabs(data.clk) >= maxBias))
653  {
654  // don't add this record with a bad clock
655  continue;
656  }
657  if (processEph)
658  {
659  // If the orbit data are predictions and we've
660  // been asked to ignore position predictions, do
661  // so. Otherwise, add the data to the store.
662  if ((!rejectPredPosFlag || data.orbitPredFlag) &&
663  !convertToOrbit(head, data, isC, eph))
664  {
665  return false;
666  }
667  }
668  if (processClk)
669  {
670  // If the clock data are predictions and we've
671  // been asked to ignore clock predictions, do
672  // so. Otherwise, add the data to the store.
673  if ((!rejectPredClockFlag || data.clockPredFlag) &&
674  !convertToClock(head, data, isC, clk))
675  {
676  return false;
677  }
678  }
679  }
680  }
681  // store the final record(s)
682  DEBUGTRACE("storing last eph");
683  if (!store(processEph, cb, eph))
684  return false;
685  DEBUGTRACE("storing last clk");
686  if (!store(processClk, cb, clk))
687  return false;
688  }
689  catch (gnsstk::Exception& exc)
690  {
691  rv = false;
692  cerr << exc << endl;
693  }
694  catch (std::exception& exc)
695  {
696  rv = false;
697  cerr << exc.what() << endl;
698  }
699  catch (...)
700  {
701  rv = false;
702  cerr << "Unknown exception" << endl;
703  }
704  return rv;
705  }
706 
707 
709  addRinexClock(const std::string& source, NavDataFactoryCallback& cb)
710  {
711  bool rv = true;
712  // We have to handle this a bit carefully. If we're not
713  // processing clock data, we still need to at least identify
714  // the data, otherwise NavLibrary/MultiFormatNavDataFactory
715  // might incorrectly handle the processing of the file.
716  bool processClk = (procNavTypes.count(NavMessageType::Clock) > 0);
717  try
718  {
719  Rinex3ClockStream is(source.c_str(), ios::in);
720  Rinex3ClockHeader head;
722  if (!is)
723  {
724  return false;
725  }
726  is >> head;
727  if (!is)
728  {
729  return false;
730  }
731 
732  // At this point, we have valid RINEX clock. Probably.
733  if (!processClk)
734  return true; // ...but the user doesn't want it.
735 
736  // check/save TimeSystem to storeTimeSystem
737  if(head.timeSystem != TimeSystem::Any &&
738  head.timeSystem != TimeSystem::Unknown)
739  {
740  // if store time system has not been set, do so
742  {
744  storeTimeSystem = head.timeSystem;
745  }
746  else if (storeTimeSystem != head.timeSystem)
747  {
748  // Don't load a RINEX clock file with a differing time system
749  cerr << "Time system mismatch in SP3/RINEX clock data "
751  << " (store) != "
752  << gnsstk::StringUtils::asString(head.timeSystem)
753  << " (file)" << endl;
754  return false;
755  }
756  }
757  else
758  {
759  head.timeSystem = TimeSystem::GPS;
760  storeTimeSystem = head.timeSystem;
761  }
762 
763  // Valid RINEX clock data with appropriate time system, go
764  // ahead and switch to using RINEX clock instead of SP3
765  // clock.
767 
768  while (is)
769  {
770  is >> data;
771  if (!is)
772  {
773  if (is.eof())
774  break;
775  else
776  return false; // some other error
777  }
778  if(data.datatype == std::string("AS"))
779  {
780  data.time.setTimeSystem(head.timeSystem);
781  OrbitDataSP3 *gps;
782  NavDataPtr clk = std::make_shared<OrbitDataSP3>();
783  // Force the message type to clock because
784  // OrbitDataSP3 defaults to Ephemeris.
785  clk->signal.messageType = NavMessageType::Clock;
786  setSignal(data.sat, clk->signal);
787  gps = dynamic_cast<OrbitDataSP3*>(clk.get());
788  gps->timeStamp = data.time;
789  // apparently the time system isn't set in
790  // Rinex3ClockData, only in the header.
791  gps->timeStamp.setTimeSystem(head.timeSystem);
792  gps->clkBias = data.bias * 1e6; // seconds to us
793  gps->biasSig = data.sig_bias;
794  gps->clkDrift = data.drift * 1e-6;
795  gps->driftSig = data.sig_drift;
796  gps->clkDrRate = data.accel;
797  gps->drRateSig = data.sig_accel;
798  if (!store(processClk, cb, clk))
799  return false;
800  }
801  }
802  }
803  catch (gnsstk::Exception& exc)
804  {
805  rv = false;
806  cerr << exc << endl;
807  }
808  catch (std::exception& exc)
809  {
810  rv = false;
811  cerr << exc.what() << endl;
812  }
813  catch (...)
814  {
815  rv = false;
816  cerr << "Unknown exception" << endl;
817  }
818  return rv;
819  }
820 
821 
822  std::string SP3NavDataFactory ::
824  {
825  if (procNavTypes.empty() ||
827  (procNavTypes.count(NavMessageType::Clock) > 0))
828  {
829  return "SP3a, SP3b, SP3c, SP3d";
830  }
831  return "";
832  }
833 
834 
836  convertToOrbit(const SP3Header& head, const SP3Data& navIn, bool isC,
837  NavDataPtr& navOut)
838  {
840  OrbitDataSP3 *gps;
841  // SP3 needs to merge multiple records, position and
842  // velocity, so we only create new objects as needed.
843  if (!navOut)
844  {
845  DEBUGTRACE("creating OrbitDataSP3");
846  navOut = std::make_shared<OrbitDataSP3>();
847  }
848  gps = dynamic_cast<OrbitDataSP3*>(navOut.get());
849  DEBUGTRACE("navIn.RecType=" << navIn.RecType);
850  DEBUGTRACE("navIn.correlationFlag=" << navIn.correlationFlag);
851  switch (navIn.RecType)
852  {
853  case 'P':
854  gps->timeStamp = navIn.time;
855  for (unsigned i = 0; i < 3; i++)
856  {
857  gps->pos[i] = navIn.x[i];
864  if (navIn.correlationFlag)
865  {
866  gps->posSig[i] = navIn.sdev[i];
867  DEBUGTRACE("navIn.sdev[" << i << "] = " << gps->posSig[i]);
868  }
869  else if (isC && (navIn.sig[i] >= 0))
870  {
871  gps->posSig[i] = ::pow(head.basePV, navIn.sig[i]);
872  DEBUGTRACE("pow(head.basePV,navIn.sig[" << i << "] = "
873  << gps->posSig[i]);
874  }
875  }
876  setSignal(navIn.sat, navOut->signal);
877  break;
878  case 'V':
879  gps->timeStamp = navIn.time;
880  for (unsigned i = 0; i < 3; i++)
881  {
882  // Yes, x. Because SP3Data stores position and
883  // velocity in separate records and the data from
884  // both goes into x.
885  gps->vel[i] = navIn.x[i];
886  if (navIn.correlationFlag)
887  gps->velSig[i] = navIn.sdev[i];
888  else if (isC && (navIn.sig[i] >= 0))
889  gps->velSig[i] = ::pow(head.basePV, navIn.sig[i]);
890  }
891  break;
892  }
893  gps->coordSystem = head.coordSystem;
894  DEBUGTRACE("setting reference frame using time "
895  << gnsstk::printTime(head.time,dts) << " "
897  gps->frame = RefFrame(gps->coordSystem, head.time);
898  return true;
899  }
900 
901 
903  convertToClock(const SP3Header& head, const SP3Data& navIn, bool isC,
904  NavDataPtr& clkOut)
905  {
906  bool rv = true;
907  OrbitDataSP3 *gps;
908  // SP3 needs to merge multiple records, position and
909  // velocity, so we only create new objects as needed.
910  if (!clkOut)
911  {
912  clkOut = std::make_shared<OrbitDataSP3>();
913  // Force the message type to clock because OrbitDataSP3
914  // defaults to Ephemeris.
915  clkOut->signal.messageType = NavMessageType::Clock;
916  }
917  gps = dynamic_cast<OrbitDataSP3*>(clkOut.get());
918  switch (navIn.RecType)
919  {
920  case 'P':
921  gps->timeStamp = navIn.time;
922  gps->clkBias = navIn.clk;
923  if (navIn.correlationFlag)
924  gps->biasSig = navIn.sdev[3] * 1e-6;
925  else if (isC && (navIn.sig[3] >= 0))
926  gps->biasSig = ::pow(head.baseClk, navIn.sig[3]) * 1e-6;
927  setSignal(navIn.sat, clkOut->signal);
928  break;
929  case 'V':
930  gps->timeStamp = navIn.time;
931  gps->clkDrift = navIn.clk * 1e-4;
932  if (navIn.correlationFlag)
933  gps->driftSig = navIn.sdev[3] * 1e-10;
934  else if (isC && (navIn.sig[3] >= 0))
935  gps->driftSig = ::pow(head.baseClk, navIn.sig[3]) * 1e-10;
936  break;
937  }
938  return rv;
939  }
940 
941 
943  store(bool process, NavDataFactoryCallback& cb, NavDataPtr& obj)
944  {
946  // only process if we have something to process.
947  if (obj)
948  {
949  DEBUGTRACE("store storing " << obj.get());
950  // check the validity
951  bool check = false;
952  bool expect = false;
953  switch (navValidity)
954  {
956  check = true;
957  expect = true;
958  break;
960  check = true;
961  expect = false;
962  break;
963  // Just treat everything else like All, which is to
964  // say, no checks.
965  default:
966  break;
967  }
968  if (check)
969  {
970  if (process)
971  {
972  if (obj->validate() == expect)
973  {
974  if (!cb.process(obj))
975  {
976  DEBUGTRACE("store failed to add nav data");
977  return false;
978  }
979  }
980  }
981  }
982  else
983  {
984  if (process)
985  {
986  if (!cb.process(obj))
987  {
988  DEBUGTRACE("store failed to add nav data");
989  return false;
990  }
991  }
992  }
993  // Clear the shared_ptr so the next time
994  // convertToOrbit is called, it creates a new one.
995  DEBUGTRACE("store resetting obj ptr, use_count=" << obj.use_count());
996  // NavData *ptr = obj.get();
997  DEBUGTRACE("DUMP BEFORE:");
998  // ptr->dump(cerr, DumpDetail::Full);
999  obj.reset();
1000  DEBUGTRACE("DUMP AFTER:");
1001  // ptr->dump(cerr, DumpDetail::Full);
1002  }
1003  return true;
1004  }
1005 
1006 
1007  // This method is roughly equivalent to the deprecated
1008  // PositionSatStore::getValue().
1010  interpolateEph(const NavMap::iterator& ti1, const NavMap::iterator& ti3,
1011  const CommonTime& when, NavDataPtr& navData)
1012  {
1014  DEBUGTRACE("start interpolating ephemeris, distance = "
1015  << std::distance(ti1,ti3));
1016  std::vector<double> tdata(2*halfOrderPos);
1017  std::vector<std::vector<double>> posData(3), posSigData(3), velData(3),
1018  velSigData(3), accData(3), accSigData(3);
1019  CommonTime firstTime(ti1->second->timeStamp);
1020  // This flag is only used to decide whether to compute sigmas
1021  // or use existing ones. It is expected that for exact time
1022  // matches, navData will already have any sigma data filled
1023  // in.
1024  bool isExact = false;
1025  unsigned idx = 0;
1026  // posData etc are 2D arrays, where the first dimension
1027  // is positional, x=0,y=1,z=2 and the 2nd dimension is
1028  // the data index for the fit.
1029  for (unsigned i = 0; i < 3; i++)
1030  {
1031  posData[i].resize(2*halfOrderPos);
1032  posSigData[i].resize(2*halfOrderPos);
1033  velData[i].resize(2*halfOrderPos);
1034  velSigData[i].resize(2*halfOrderPos);
1035  accData[i].resize(2*halfOrderPos);
1036  accSigData[i].resize(2*halfOrderPos);
1037  }
1038  DEBUGTRACE("resized");
1039  bool haveVel = false, haveAcc = false;
1040  NavMap::iterator ti2;
1041  for (ti2 = ti1, idx=0; ti2 != ti3; ++ti2, ++idx)
1042  {
1043  DEBUGTRACE("idx=" << idx);
1044  tdata[idx] = ti2->second->timeStamp - firstTime;
1045  if ((idx == halfOrderPos) && (ti2->second->timeStamp == when))
1046  isExact = true;
1047  OrbitDataSP3 *nav = dynamic_cast<OrbitDataSP3*>(
1048  ti2->second.get());
1049  DEBUGTRACE("nav=" << nav);
1050  // ti2->second->dump(cerr, DumpDetail::Full);
1051  for (unsigned i = 0; i < 3; i++)
1052  {
1053  DEBUGTRACE("i=" << i);
1054  DEBUGTRACE(posData.size() << " " << velData.size() << " "
1055  << accData.size());
1056  DEBUGTRACE(nav->pos.size() << " " << nav->vel.size() << " "
1057  << nav->acc.size());
1058  posData[i][idx] = nav->pos[i];
1059  velData[i][idx] = nav->vel[i];
1060  accData[i][idx] = nav->acc[i];
1061  posSigData[i][idx] = nav->posSig[i];
1062  velSigData[i][idx] = nav->velSig[i];
1063  accSigData[i][idx] = nav->accSig[i];
1064  haveVel |= (nav->vel[i] != 0.0);
1065  haveAcc |= (nav->acc[i] != 0.0);
1066  }
1067  }
1068  double dt = when - firstTime, err;
1069  OrbitDataSP3 *osp3 = dynamic_cast<OrbitDataSP3*>(navData.get());
1070  DEBUGTRACE(printTime(when, "when=%Y/%02m/%02d %02H:%02M:%02S"));
1071  DEBUGTRACE(printTime(firstTime, "firstTime=%Y/%02m/%02d %02H:%02M:%02S"));
1072  DEBUGTRACE(setprecision(20) << " dt=" << dt);
1073  if (DebugTrace::enabled)
1074  {
1075  for (unsigned i = 0; i < tdata.size(); i++)
1076  {
1077  DEBUGTRACE("i=" << i << " times=" << tdata[i]);
1078  DEBUGTRACE("P=" << posData[0][i] << " " << posData[1][i] << " "
1079  << posData[2][i]);
1080  DEBUGTRACE("V=" << velData[0][i] << " " << velData[1][i] << " "
1081  << velData[2][i]);
1082  DEBUGTRACE("A=" << accData[0][i] << " " << accData[1][i] << " "
1083  << accData[2][i]);
1084  }
1085  }
1086  DEBUGTRACE("haveVelocity=" << haveVel << " haveAcceleration="
1087  << haveAcc);
1088  // Interpolate XYZ position/velocity/acceleration.
1089  for (unsigned i = 0; i < 3; i++)
1090  {
1091  if (haveVel && haveAcc)
1092  {
1093  osp3->pos[i] = LagrangeInterpolation(tdata,posData[i],dt,err);
1094  osp3->vel[i] = LagrangeInterpolation(tdata,velData[i],dt,err);
1095  osp3->acc[i] = LagrangeInterpolation(tdata,accData[i],dt,err);
1096  unsigned Nhi = halfOrderPos, Nlow=halfOrderPos-1;
1097  DEBUGTRACE("!isExact sigP[" << i << "][" << Nhi << "] = "
1098  << posSigData[i][Nhi]);
1099  DEBUGTRACE(" sigP[" << i << "][" << Nlow << "] = "
1100  << posSigData[i][Nlow]);
1101  DEBUGTRACE(" sigV[" << i << "][" << Nhi << "] = "
1102  << velSigData[i][Nhi]);
1103  DEBUGTRACE(" sigV[" << i << "][" << Nlow << "] = "
1104  << velSigData[i][Nlow]);
1105  DEBUGTRACE(" sigA[" << i << "][" << Nhi << "] = "
1106  << accSigData[i][Nhi]);
1107  DEBUGTRACE(" sigA[" << i << "][" << Nlow << "] = "
1108  << accSigData[i][Nlow]);
1109  if (!isExact)
1110  {
1111  osp3->posSig[i] = RSS(posSigData[i][halfOrderPos-1],
1112  posSigData[i][halfOrderPos]);
1113  osp3->velSig[i] = RSS(velSigData[i][halfOrderPos-1],
1114  velSigData[i][halfOrderPos]);
1115  osp3->accSig[i] = RSS(accSigData[i][halfOrderPos-1],
1116  accSigData[i][halfOrderPos]);
1117  DEBUGTRACE("1 RSS(posSigData[" << i << "][" << (halfOrderPos-1)
1118  << "],posSigData[" << i << "][" << halfOrderPos
1119  << "]) = " << osp3->posSig[i]);
1120  }
1121  }
1122  else if (haveVel && !haveAcc)
1123  {
1124  osp3->pos[i] = LagrangeInterpolation(tdata,posData[i],dt,err);
1125  LagrangeInterpolation(tdata, velData[i], dt, osp3->vel[i],
1126  osp3->acc[i]);
1127  osp3->acc[i] *= 0.1;
1128  unsigned Nhi = halfOrderPos, Nlow=halfOrderPos-1;
1129  DEBUGTRACE("!isExact sigP[" << i << "][" << Nhi << "] = "
1130  << posSigData[i][Nhi]);
1131  DEBUGTRACE(" sigP[" << i << "][" << Nlow << "] = "
1132  << posSigData[i][Nlow]);
1133  DEBUGTRACE(" sigV[" << i << "][" << Nhi << "] = "
1134  << velSigData[i][Nhi]);
1135  DEBUGTRACE(" sigV[" << i << "][" << Nlow << "] = "
1136  << velSigData[i][Nlow]);
1137  DEBUGTRACE(" sigA[" << i << "][" << Nhi << "] = "
1138  << accSigData[i][Nhi]);
1139  DEBUGTRACE(" sigA[" << i << "][" << Nlow << "] = "
1140  << accSigData[i][Nlow]);
1141  if (!isExact)
1142  {
1143  osp3->posSig[i] = RSS(posSigData[i][halfOrderPos-1],
1144  posSigData[i][halfOrderPos]);
1145  osp3->velSig[i] = RSS(velSigData[i][halfOrderPos-1],
1146  velSigData[i][halfOrderPos]);
1147  }
1148  DEBUGTRACE("2 RSS(posSigData[" << i << "][" << (halfOrderPos-1)
1149  << "],posSigData[" << i << "][" << halfOrderPos
1150  << "]) = " << osp3->posSig[i]);
1151  }
1152  else
1153  {
1154  // have position, must derive velocity and acceleration
1155  LagrangeInterpolation(tdata, posData[i], dt, osp3->pos[i],
1156  osp3->vel[i]);
1157  osp3->vel[i] *= 10000.; // km/sec to dm/sec
1158  // PositionSatStore doesn't derive
1159  // acceleration in this case, near as I can
1160  // tell.
1161  if (!isExact)
1162  {
1163  osp3->posSig[i] = RSS(posSigData[i][halfOrderPos-1],
1164  posSigData[i][halfOrderPos]);
1165  }
1166  DEBUGTRACE("3 RSS(posSigData[" << i << "][" << (halfOrderPos-1)
1167  << "],posSigData[" << i << "][" << halfOrderPos
1168  << "]) = " << osp3->posSig[i]);
1169  }
1170  } // for (unsigned i = 0; i < 3; i++)
1171  if (DebugTrace::enabled)
1172  {
1173  for (unsigned i = 0; i < 3; i++)
1174  {
1175  DEBUGTRACE("pos[" << i << "]=" << osp3->pos[i]
1176  << " vel[" << i << "]=" << osp3->vel[i]
1177  << " acc[" << i << "]=" << osp3->acc[i]);
1178  }
1179  }
1180  }
1181 
1182 
1184  interpolateClk(const NavMap::iterator& ti1, const NavMap::iterator& ti3,
1185  const CommonTime& when, NavDataPtr& navData)
1186  {
1188  DEBUGTRACE("start interpolating clock, distance = "
1189  << std::distance(ti1,ti3));
1190  unsigned Nhi = halfOrderClk, Nlow = halfOrderClk-1;
1191  std::vector<double> tdata(2*halfOrderClk),
1192  biasData(2*halfOrderClk), biasSigData(2*halfOrderClk),
1193  driftData(2*halfOrderClk), driftSigData(2*halfOrderClk),
1194  drRateData(2*halfOrderClk), drRateSigData(2*halfOrderClk);
1195  CommonTime firstTime(ti1->second->timeStamp);
1196  // This flag is only used to decide whether to compute sigmas
1197  // or use existing ones. It is expected that for exact time
1198  // matches, navData will already have any sigma data filled
1199  // in.
1200  bool isExact = false;
1201  unsigned idx = 0;
1202  bool haveDrift = false, haveDriftRate = false;
1203  NavMap::iterator ti2;
1204  for (ti2 = ti1, idx=0; ti2 != ti3; ++ti2, ++idx)
1205  {
1206  DEBUGTRACE("idx=" << idx);
1207  tdata[idx] = ti2->second->timeStamp - firstTime;
1208  if ((idx == halfOrderClk) && (ti2->second->timeStamp == when))
1209  isExact = true;
1210  OrbitDataSP3 *nav = dynamic_cast<OrbitDataSP3*>(
1211  ti2->second.get());
1212  DEBUGTRACE("nav=" << nav);
1213  // ti2->second->dump(cerr, DumpDetail::Full);
1214  biasData[idx] = nav->clkBias;
1215  driftData[idx] = nav->clkDrift;
1216  drRateData[idx] = nav->clkDrRate;
1217  biasSigData[idx] = nav->biasSig;
1218  driftSigData[idx] = nav->driftSig;
1219  drRateSigData[idx] = nav->drRateSig;
1220  haveDrift |= (nav->clkDrift != 0.0);
1221  haveDriftRate |= (nav->clkDrRate != 0.0);
1222  }
1223  double dt = when - firstTime, err, slope,
1224  slopedt = tdata[Nhi]-tdata[Nlow];
1225  OrbitDataSP3 *osp3 = dynamic_cast<OrbitDataSP3*>(navData.get());
1226  DEBUGTRACE(setprecision(20) << " dt=" << dt);
1227  gnsstk::InvalidRequest unkType(
1228  "Clock interpolation type " +
1229  StringUtils::asString(static_cast<int>(interpType)) +
1230  " is not supported");
1231  if (haveDrift)
1232  {
1233  switch (interpType)
1234  {
1236  osp3->clkBias = LagrangeInterpolation(tdata,biasData,dt,err);
1237  osp3->clkDrift = LagrangeInterpolation(tdata,driftData,dt,err);
1238  break;
1239  case ClkInterpType::Linear:
1240  slope = (biasData[Nhi]-biasData[Nlow]) / slopedt;
1241  osp3->clkBias = biasData[Nlow] + slope*(dt-tdata[Nlow]);
1242  slope = (driftData[Nhi]-driftData[Nlow]) / slopedt;
1243  osp3->clkDrift = driftData[Nlow] + slope*(dt-tdata[Nlow]);
1244  break;
1245  default:
1246  GNSSTK_THROW(unkType);
1247  break;
1248  }
1249  // if isExact, we just use the already populated values.
1250  if (!isExact)
1251  {
1252  osp3->biasSig = RSS(biasSigData[Nlow], biasSigData[Nhi]);
1253  DEBUGTRACE("biasSig = " << osp3->biasSig)
1254  DEBUGTRACE(" driftSig = " << osp3->driftSig)
1255  DEBUGTRACE(" drRateSig = " << osp3->drRateSig);
1256  }
1257  osp3->driftSig = RSS(driftSigData[Nlow], driftSigData[Nhi]);
1258  }
1259  else
1260  {
1261  // No drift, we have to derive it numerically
1262  switch (interpType)
1263  {
1265  LagrangeInterpolation(tdata, biasData, dt, osp3->clkBias,
1266  osp3->clkDrift);
1267  break;
1268  case ClkInterpType::Linear:
1269  slope = (biasData[Nhi]-biasData[Nlow]) / slopedt;
1270  osp3->clkDrift = slope;
1271  osp3->clkBias = biasData[Nlow] + slope*(dt-tdata[Nlow]);
1272  break;
1273  default:
1274  GNSSTK_THROW(unkType);
1275  break;
1276  }
1277  // if isExact, we just use the already populated values.
1278  if (!isExact)
1279  {
1280  osp3->biasSig = RSS(biasSigData[Nlow], biasSigData[Nhi]);
1281  DEBUGTRACE("biasSig = " << osp3->biasSig);
1282  }
1283  // linear interpolation of drift
1288  osp3->driftSig = osp3->biasSig / slopedt;
1289  }
1290 
1291  if (haveDriftRate)
1292  {
1293  switch (interpType)
1294  {
1296  osp3->clkDrRate = LagrangeInterpolation(tdata,drRateData,dt,err);
1297  break;
1298  case ClkInterpType::Linear:
1299  slope = (drRateData[Nhi]-drRateData[Nlow]) / slopedt;
1300  osp3->clkDrRate = drRateData[Nlow] + slope*(dt-tdata[Nlow]);
1301  break;
1302  default:
1303  GNSSTK_THROW(unkType);
1304  break;
1305  }
1306  // if isExact, we just use the already populated values.
1307  if (!isExact)
1308  {
1309  osp3->drRateSig = RSS(drRateSigData[Nlow], drRateSigData[Nhi]);
1310  }
1311  }
1312  else if (haveDrift)
1313  {
1314  // must interpolate drift to get drift rate
1315  switch (interpType)
1316  {
1318  LagrangeInterpolation(tdata,driftData,dt,err,osp3->clkDrRate);
1319  break;
1320  case ClkInterpType::Linear:
1321  osp3->clkDrRate = (driftData[Nhi]-driftData[Nlow]) / slopedt;
1322  break;
1323  default:
1324  GNSSTK_THROW(unkType);
1325  break;
1326  }
1327  osp3->drRateSig = osp3->driftSig / slopedt;
1328  }
1329  }
1330 
1331 
1333  setSignal(const SatID& sat, NavMessageID& signal)
1334  {
1335  bool rv = true;
1336  signal.sat = sat;
1337  signal.xmitSat = sat;
1338  signal.system = sat.system;
1340  // make our best guess.
1341  switch (sat.system)
1342  {
1343  case SatelliteSystem::GPS:
1344  signal.obs = oidGPS;
1345  signal.nav = ntGPS;
1346  break;
1348  signal.obs = oidGalileo;
1349  signal.nav = ntGalileo;
1350  break;
1351  case SatelliteSystem::QZSS:
1352  signal.obs = oidQZSS;
1353  signal.nav = ntQZSS;
1354  break;
1356  signal.obs = oidGLONASS;
1357  signal.nav = ntGLONASS;
1360  break;
1362  signal.obs = oidBeiDou;
1363  signal.nav = ntBeiDou;
1364  break;
1365  default:
1370  signal.nav = NavType::Unknown;
1371  rv = false;
1372  break;
1373  }
1374  return rv;
1375  }
1376 
1377 
1379  transNavMsgID(const NavMessageID& nmidIn, NavMessageID& nmidOut)
1380  {
1381  nmidOut = nmidIn; // copy all the original data first.
1382  return setSignal(nmidIn.sat, nmidOut);
1383  }
1384 
1385 
1388  {
1389  if (useRC == !useSP3clock)
1390  return;
1391  useSP3clock = !useRC;
1392  clearClock();
1393  }
1394 
1395 
1397  setClockInterpOrder(unsigned int order)
1398  {
1400  halfOrderClk = (order+1)/2;
1401  else
1402  halfOrderClk = 1;
1403  }
1404 
1405 
1408  {
1410  halfOrderClk = 5;
1411  }
1412 
1413 
1416  {
1418  halfOrderClk = 1;
1419  }
1420 
1421 
1422  double SP3NavDataFactory ::
1423  getPositionTimeStep(const SatID& sat) const
1424  {
1426  return nomTimeStep(key);
1427  }
1428 
1429 
1430  double SP3NavDataFactory ::
1431  getClockTimeStep(const SatID& sat) const
1432  {
1434  return nomTimeStep(key);
1435  }
1436 
1437 
1438  double SP3NavDataFactory ::
1439  nomTimeStep(const NavMessageID& nmid) const
1440  {
1442  auto dataIt = data.find(nmid.messageType);
1443  // map delta time * 100 to a count
1444  std::map<long,unsigned long> stepCount;
1445  // reverse of stepCount
1446  std::map<unsigned long,long> countStep;
1447  if (dataIt == data.end())
1448  {
1449  DEBUGTRACE("no data for nav message type");
1450  return false;
1451  }
1452  // To support wildcard signals, we need to do a linear search.
1453  for (const auto& sati : dataIt->second)
1454  {
1455  if (sati.first != nmid)
1456  continue; // skip non matches
1457  DEBUGTRACE("found a match");
1458  auto ti1 = sati.second.begin();
1459  auto ti2 = std::next(ti1);
1460  while (ti2 != sati.second.end())
1461  {
1462  double diff = ti2->first - ti1->first;
1463  DEBUGTRACE("diff=" << diff);
1464  stepCount[(long)(diff*100)]++;
1465  ++ti1;
1466  ++ti2;
1467  }
1468  }
1469  // Remap stepCount to countStep, which puts the steps in
1470  // order of how common they are. May result in overwrites,
1471  // but we don't really care.
1472  for (const auto& sci : stepCount)
1473  {
1474  countStep[sci.second] = sci.first;
1475  }
1476  DEBUGTRACE("countStep.empty()=" << countStep.empty());
1477  if (!countStep.empty())
1478  {
1479  // change the scale back to seconds.
1480  return countStep.begin()->second / 100.0;
1481  }
1482  return 0.0;
1483  }
1484 
1485 
1487  dumpConfig(std::ostream& s) const
1488  {
1489  // Not sure why initialTime is being set to time system any
1490  // and final time is not, but that's how the original code in
1491  // TabularSatStore was.
1495  static const std::string fmt(
1496  "%4F %w %10.3g %4Y/%02m/%02d %2H:%02M:%02S %P");
1497  s << "Dump SP3NavDataFactory:" << endl
1498  << (rejectBadPosFlag ? " Reject":" Do not reject")
1499  << " bad positions." << endl
1500  << (rejectBadClockFlag ? " Reject":" Do not reject")
1501  << " bad clocks." << endl
1502  << (rejectPredPosFlag ? " Reject":" Do not reject")
1503  << " predicted positions." << endl
1504  << (rejectPredClockFlag ? " Reject":" Do not reject")
1505  << " predicted clocks." << endl
1506  << "Position data:" << endl
1507  << " Interpolation is Lagrange, of order " << getPositionInterpOrder()
1508  << " (" << halfOrderPos << " points on each side)" << endl
1509  << " Data stored for " << numSatellites() << " satellites" << endl
1510  << " Time span of data: "
1511  << " Initial time is " << printTime(initialTime,fmt) << endl;
1514  {
1515  s << "(there are no time limits)" << endl;
1516  }
1517  else
1518  {
1519  s << " FROM " << printTime(initialTime,fmt) << " TO "
1520  << printTime(finalTime,fmt) << endl;
1521  }
1522  // The original TabularSatStore determined whether it had
1523  // position, velocity, clock bias and drift at load time, but
1524  // SP3NavDataFactory delays that determination until it's
1525  // ready to interpolate the data. The reason for this is
1526  // that it's possible to load one file that has the data and
1527  // another that does not. As such, we don't dump the flags
1528  // we don't have.
1529  s << " Checking for data gaps? ";
1530  if (checkDataGapPos)
1531  {
1532  s << "yes; gap interval is " << fixed << setprecision(2)
1533  << gapIntervalPos;
1534  }
1535  else
1536  {
1537  s << "no";
1538  }
1539  s << endl << " Checking data interval? ";
1540  if (checkIntervalPos)
1541  {
1542  s << "yes; max interval is " << fixed << setprecision(2)
1543  << maxIntervalPos;
1544  }
1545  else
1546  {
1547  s << "no";
1548  }
1549  s << endl
1550  << "Clock data:" << endl
1551  << " Interpolation is ";
1552  switch (interpType)
1553  {
1554  case ClkInterpType::Linear:
1555  s << "Linear." << endl;
1556  break;
1558  s << "Lagrange, of order " << getClockInterpOrder() << " ("
1559  << halfOrderClk << " points on each side)" << endl;
1560  break;
1561  default:
1562  s << "???" << endl;
1563  break;
1564  }
1565  s << " Checking for data gaps? ";
1566  if (checkDataGapClk)
1567  {
1568  s << "yes; gap interval is " << fixed << setprecision(2)
1569  << gapIntervalClk;
1570  }
1571  else
1572  {
1573  s << "no";
1574  }
1575  s << endl << " Checking data interval? ";
1576  if (checkIntervalClk)
1577  {
1578  s << "yes; max interval is " << fixed << setprecision(2)
1579  << maxIntervalClk;
1580  }
1581  else
1582  {
1583  s << "no";
1584  }
1585  s << endl
1586  << "End dump SP3NavDataFactory." << endl;
1587  }
1588 
1589 } // namespace gnsstk
gnsstk::SP3NavDataFactory::addDataSource
bool addDataSource(const std::string &source) override
Definition: SP3NavDataFactory.cpp:556
gnsstk::SP3Data::x
double x[3]
The three-vector for position | velocity (m | dm/s).
Definition: SP3Data.hpp:122
gnsstk::NavDataPtr
std::shared_ptr< NavData > NavDataPtr
Factories instantiate these in response to find() requests.
Definition: NavData.hpp:62
gnsstk::NavSignalID::nav
NavType nav
Navigation message structure of this signal.
Definition: NavSignalID.hpp:96
gnsstk::OrbitDataSP3::posSig
Triple posSig
Standard deviation of position.
Definition: OrbitDataSP3.hpp:91
gnsstk::NavType::Unknown
@ Unknown
Uninitialized value.
gnsstk::NavMessageType::Clock
@ Clock
SV Clock offset data. Currently only used by SP3.
gnsstk::Rinex3ClockStream
Definition: Rinex3ClockStream.hpp:59
gnsstk::SP3NavDataFactory::store
bool store(bool process, NavDataFactoryCallback &cb, NavDataPtr &obj)
Definition: SP3NavDataFactory.cpp:943
gnsstk::NavMessageID
Class used to identify/categorize navigation message data.
Definition: NavMessageID.hpp:52
gnsstk::SP3NavDataFactory::interpolateClk
void interpolateClk(const NavMap::iterator &ti1, const NavMap::iterator &ti3, const CommonTime &when, NavDataPtr &navData)
Definition: SP3NavDataFactory.cpp:1184
gnsstk::SP3NavDataFactory::halfOrderClk
unsigned halfOrderClk
Definition: SP3NavDataFactory.hpp:492
SP3Header.hpp
gnsstk::SP3Header::basePV
double basePV
Base used in Pos or Vel (mm or 10**-4mm/sec)
Definition: SP3Header.hpp:191
gnsstk::TrackingCode::L1CD
@ L1CD
Modernized GPS L1C civil code tracking (data)
gnsstk::OrbitDataSP3::driftSig
double driftSig
SV clock drift std deviation in microseconds/sec.
Definition: OrbitDataSP3.hpp:99
gnsstk::TrackingCode::MPA
@ MPA
gnsstk::TrackingCode::NSCA
@ NSCA
gnsstk::NavDataFactoryCallback::process
virtual bool process(const NavDataPtr &navOut)
Definition: NavDataFactoryCallback.hpp:60
gnsstk::SP3NavDataFactory::setClockLinearInterp
void setClockLinearInterp()
Definition: SP3NavDataFactory.cpp:1415
gnsstk::CarrierBand::G1
@ G1
GLONASS G1.
gnsstk::SP3NavDataFactory::getClockTimeStep
double getClockTimeStep(const SatID &sat) const
Definition: SP3NavDataFactory.cpp:1431
SP3Data.hpp
gnsstk::NavSatelliteID::isWild
bool isWild() const override
Return true if any of the fields are set to match wildcards.
Definition: NavSatelliteID.cpp:166
L1
gnsstk::Matrix< double > L1
Definition: Matrix_LUDecomp_T.cpp:46
gnsstk::NavType::GPSMNAV
@ GPSMNAV
gnsstk::Rinex3ClockHeader
Definition: Rinex3ClockHeader.hpp:64
gnsstk::Triple::size
size_t size(void) const
Return the size of this object.
Definition: Triple.hpp:240
gnsstk::NavType::BeiDou_D1
@ BeiDou_D1
gnsstk::SP3NavDataFactory::addRinexClock
bool addRinexClock(const std::string &source, NavDataFactoryCallback &cb)
Definition: SP3NavDataFactory.cpp:709
gnsstk::TrackingCode::E1B
@ E1B
Galileo E1-B signal, supporting OS/HAS/SoL.
gnsstk::NavType::GalINAV
@ GalINAV
gnsstk::CarrierBand::E5b
@ E5b
Galileo E5b.
gnsstk::OrbitDataSP3::vel
Triple vel
ECEF velocity (dm/s) of satellite at time.
Definition: OrbitDataSP3.hpp:92
gnsstk::SP3NavDataFactory::ntGLONASS
static const GNSSTK_EXPORT NavType ntGLONASS
Definition: SP3NavDataFactory.hpp:71
gnsstk::SP3Header::coordSystem
std::string coordSystem
Coordinate System of the data.
Definition: SP3Header.hpp:184
NavDataFactoryStoreCallback.hpp
gnsstk::NavMessageID::messageType
NavMessageType messageType
Definition: NavMessageID.hpp:97
gnsstk::OrbitDataSP3::copyXV
void copyXV(const OrbitDataSP3 &right)
Definition: OrbitDataSP3.cpp:58
gnsstk::SP3NavDataFactory::checkIntervalClk
bool checkIntervalClk
Definition: SP3NavDataFactory.hpp:474
gnsstk::NavSatelliteID
Definition: NavSatelliteID.hpp:57
DEBUGTRACE
#define DEBUGTRACE(EXPR)
Definition: DebugTrace.hpp:119
gnsstk::OrbitDataSP3::velSig
Triple velSig
Standard deviation of velocity.
Definition: OrbitDataSP3.hpp:93
Rinex3ClockStream.hpp
gnsstk::TrackingCode::Y
@ Y
Encrypted legacy GPS precise code.
dts
static const std::string dts("%Y/%02m/%02d %02H:%02M:%02S %3j %P")
debug time string
gnsstk::SP3NavDataFactory::checkDataGapPos
bool checkDataGapPos
Definition: SP3NavDataFactory.hpp:440
gnsstk::Exception::what
std::string what() const
Dump to a string.
Definition: Exception.cpp:193
gnsstk::SP3NavDataFactory::findGeneric
bool findGeneric(NavMessageType nmt, const NavSatelliteID &nsid, const CommonTime &when, NavDataPtr &navData)
Definition: SP3NavDataFactory.cpp:272
gnsstk::CarrierBand::Any
@ Any
Used to match any carrier band.
gnsstk::SP3NavDataFactory::getPositionInterpOrder
unsigned int getPositionInterpOrder() const
Get current interpolation order for the position table.
Definition: SP3NavDataFactory.hpp:293
gnsstk::SP3Data::time
CommonTime time
Time of epoch for this record.
Definition: SP3Data.hpp:121
gnsstk::SatID
Definition: SatID.hpp:89
gnsstk::TrackingCode::L5I
@ L5I
Modernized GPS L5 civil in-phase.
gnsstk::TimeSystem::Any
@ Any
wildcard; allows comparison with any other type
gnsstk::TrackingCode::Mprime
@ Mprime
gnsstk::StringUtils::asString
std::string asString(IonexStoreStrategy e)
Convert a IonexStoreStrategy to a whitespace-free string name.
Definition: IonexStoreStrategy.cpp:46
gnsstk::SP3NavDataFactory::rejectPredPosFlag
bool rejectPredPosFlag
Definition: SP3NavDataFactory.hpp:511
gnsstk::SP3NavDataFactory::oidGPS
static const GNSSTK_EXPORT ObsID oidGPS
Generic ObsIDs for each GNSS.
Definition: SP3NavDataFactory.hpp:68
gnsstk::OrbitDataSP3::clkBias
double clkBias
SV clock bias in microseconds.
Definition: OrbitDataSP3.hpp:96
gnsstk::CommonTime::setTimeSystem
CommonTime & setTimeSystem(TimeSystem timeSystem)
Definition: CommonTime.hpp:195
gnsstk::OrbitDataSP3::accSig
Triple accSig
Standard deviation of acceleration.
Definition: OrbitDataSP3.hpp:95
gnsstk::NavType::GloCivilF
@ GloCivilF
gnsstk::CommonTime::BEGINNING_OF_TIME
static const GNSSTK_EXPORT CommonTime BEGINNING_OF_TIME
earliest representable CommonTime
Definition: CommonTime.hpp:102
gnsstk::SP3NavDataFactory::convertToOrbit
static bool convertToOrbit(const SP3Header &head, const SP3Data &navIn, bool isC, NavDataPtr &navOut)
Definition: SP3NavDataFactory.cpp:836
gnsstk::SP3Data::correlationFlag
bool correlationFlag
data for optional P|V Correlation record
Definition: SP3Data.hpp:135
gnsstk::SP3Data::sdev
unsigned sdev[4]
Definition: SP3Data.hpp:138
gnsstk::SP3NavDataFactory::ntQZSS
static const GNSSTK_EXPORT NavType ntQZSS
Definition: SP3NavDataFactory.hpp:71
gnsstk::SVHealth
SVHealth
Identify different types of SV health states.
Definition: SVHealth.hpp:52
gnsstk::NavValidityType
NavValidityType
Definition: NavValidityType.hpp:53
gnsstk::SP3Header::time
CommonTime time
Time of first Epoch in file.
Definition: SP3Header.hpp:180
gnsstk::RefFrame
Definition: RefFrame.hpp:53
gnsstk::NavSearchOrder
NavSearchOrder
Specify the behavior of nav data searches in NavLibrary/NavDataFactory.
Definition: NavSearchOrder.hpp:51
gnsstk::SP3NavDataFactory::getFactoryFormats
std::string getFactoryFormats() const override
Return a comma-separated list of formats supported by this factory.
Definition: SP3NavDataFactory.cpp:823
gnsstk::TrackingCode::MDP
@ MDP
Modernized GPS military unique code.
gnsstk::CarrierBand::Unknown
@ Unknown
Uninitialized value.
gnsstk::TimeSystem::Unknown
@ Unknown
unknown time frame; for legacy code compatibility
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::SP3NavDataFactory::maxIntervalPos
double maxIntervalPos
Definition: SP3NavDataFactory.hpp:467
gnsstk::NavType::GPSLNAV
@ GPSLNAV
gnsstk::SP3NavDataFactory::maxIntervalClk
double maxIntervalClk
Definition: SP3NavDataFactory.hpp:480
gnsstk::NavDataFactoryWithStore::count
virtual size_t count(const NavMessageID &nmid) const
Definition: NavDataFactoryWithStore.cpp:1022
gnsstk::CarrierBand::L2
@ L2
GPS L2, QZSS L2.
gnsstk::SP3NavDataFactory::interpType
ClkInterpType interpType
Clock data interpolation method.
Definition: SP3NavDataFactory.hpp:520
gnsstk::TrackingCode::Standard
@ Standard
Legacy Glonass civil signal.
gnsstk::SP3NavDataFactory::oidGLONASS
static const GNSSTK_EXPORT ObsID oidGLONASS
Definition: SP3NavDataFactory.hpp:68
MiscMath.hpp
gnsstk::NavData::timeStamp
CommonTime timeStamp
Definition: NavData.hpp:173
gnsstk::NavDataFactoryCallback
Definition: NavDataFactoryCallback.hpp:54
gnsstk::Exception
Definition: Exception.hpp:151
gnsstk::ObservationType::NavMsg
@ NavMsg
Navigation Message data.
gnsstk::TrackingCode::E5aI
@ E5aI
Galileo E5a I code.
gnsstk::SatelliteSystem::GPS
@ GPS
gnsstk::TrackingCode::CA
@ CA
Legacy GPS civil code.
gnsstk::NavDataFactoryWithStore::initialTime
CommonTime initialTime
Store the earliest applicable orbit time here, by addNavData.
Definition: NavDataFactoryWithStore.hpp:463
gnsstk::CommonTime::END_OF_TIME
static const GNSSTK_EXPORT CommonTime END_OF_TIME
latest representable CommonTime
Definition: CommonTime.hpp:104
gnsstk::SP3NavDataFactory::find
bool find(const NavMessageID &nmid, const CommonTime &when, NavDataPtr &navOut, SVHealth xmitHealth, NavValidityType valid, NavSearchOrder order) override
Definition: SP3NavDataFactory.cpp:238
gnsstk::SP3Data::RecType
char RecType
Data type indicator. P position, V velocity, * epoch.
Definition: SP3Data.hpp:119
gnsstk::DebugTrace::enabled
static GNSSTK_EXPORT std::atomic< bool > enabled
If true, debugging/trace output will be printed to stderr.
Definition: DebugTrace.hpp:86
gnsstk::TrackingCode::MD
@ MD
gnsstk::NavSignalID::obs
ObsID obs
Carrier, tracking code, etc.
Definition: NavSignalID.hpp:95
gnsstk::SP3NavDataFactory::setSignal
static bool setSignal(const SatID &sat, NavMessageID &signal)
Definition: SP3NavDataFactory.cpp:1333
gnsstk::NavSignalID::system
SatelliteSystem system
GNSS for this signal.
Definition: NavSignalID.hpp:94
gnsstk::NavDataFactoryStoreCallback
Definition: NavDataFactoryStoreCallback.hpp:52
gnsstk::SP3NavDataFactory::rejectPredClockFlag
bool rejectPredClockFlag
Definition: SP3NavDataFactory.hpp:517
gnsstk::SP3NavDataFactory::ntBeiDou
static const GNSSTK_EXPORT NavType ntBeiDou
Definition: SP3NavDataFactory.hpp:72
gnsstk::SP3NavDataFactory::checkIntervalPos
bool checkIntervalPos
Definition: SP3NavDataFactory.hpp:461
gnsstk::OrbitDataSP3::coordSystem
std::string coordSystem
Copy of SP3Header::coordSystem since it might not translate.
Definition: OrbitDataSP3.hpp:103
gnsstk::CarrierBand::B3
@ B3
BeiDou B3.
gnsstk::CarrierBand::B1
@ B1
BeiDou B1.
gnsstk::NavType::GloCivilC
@ GloCivilC
gnsstk::OrbitDataSP3::pos
Triple pos
ECEF position (km) of satellite at time.
Definition: OrbitDataSP3.hpp:90
gnsstk::CarrierBand::G3
@ G3
GLONASS G3.
Rinex3ClockData.hpp
gnsstk::SP3NavDataFactory::checkDataGapClk
bool checkDataGapClk
Definition: SP3NavDataFactory.hpp:450
gnsstk::NavValidityType::InvalidOnly
@ InvalidOnly
Only load/find nav messages that fail validity checks.
gnsstk::NavDataFactory::navValidity
NavValidityType navValidity
Definition: NavDataFactory.hpp:390
gnsstk::SP3NavDataFactory::rejectBadClockFlag
bool rejectBadClockFlag
Definition: SP3NavDataFactory.hpp:507
gnsstk::NavValidityType::ValidOnly
@ ValidOnly
Only load/find nav messages that pass validity checks.
gnsstk::SP3NavDataFactory::getPositionTimeStep
double getPositionTimeStep(const SatID &sat) const
Definition: SP3NavDataFactory.cpp:1423
gnsstk::ObsID
Definition: ObsID.hpp:82
gnsstk::SP3NavDataFactory::useRinexClockData
void useRinexClockData(bool useRC=true)
Definition: SP3NavDataFactory.cpp:1387
gnsstk::SP3NavDataFactory::convertToClock
static bool convertToClock(const SP3Header &head, const SP3Data &navIn, bool isC, NavDataPtr &clkOut)
Definition: SP3NavDataFactory.cpp:903
example4.err
err
Definition: example4.py:126
gnsstk::NavType::GPSCNAVL2
@ GPSCNAVL2
gnsstk::SP3NavDataFactory::ClkInterpType
ClkInterpType
Types of interpolation that can be used on the clock data.
Definition: SP3NavDataFactory.hpp:62
gnsstk::NavSatelliteID::sat
SatID sat
ID of satellite to which the nav data applies.
Definition: NavSatelliteID.hpp:169
gnsstk::SP3Stream
Definition: SP3Stream.hpp:61
gnsstk::SP3Data::clk
double clk
The clock bias or drift for P|V (microsec|1).
Definition: SP3Data.hpp:123
gnsstk::CommonTime
Definition: CommonTime.hpp:84
gnsstk::SP3NavDataFactory::setClockInterpOrder
void setClockInterpOrder(unsigned int order)
Definition: SP3NavDataFactory.cpp:1397
gnsstk::TrackingCode::L2CML
@ L2CML
Modernized GPS L2 civil M+L combined tracking.
gnsstk::maxBias
const double maxBias
A clock bias >= this is considered bad.
Definition: SP3NavDataFactory.cpp:80
gnsstk::SP3Data::sat
SatID sat
Satellite ID.
Definition: SP3Data.hpp:120
gnsstk::TrackingCode::MprimePA
@ MprimePA
gnsstk::SP3NavDataFactory::transNavMsgID
static bool transNavMsgID(const NavMessageID &nmidIn, NavMessageID &nmidOut)
Definition: SP3NavDataFactory.cpp:1379
gnsstk::TrackingCode::B1I
@ B1I
BeiDou B1 I code.
gnsstk::TimeSystem
TimeSystem
Definition of various time systems.
Definition: TimeSystem.hpp:51
gnsstk::SP3NavDataFactory::process
bool process(const std::string &filename, NavDataFactoryCallback &cb) override
Definition: SP3NavDataFactory.cpp:566
gnsstk::TrackingCode::L3OCD
@ L3OCD
Glonass L3 I code.
example6.valid
valid
Definition: example6.py:20
gnsstk::CarrierBand::L1
@ L1
GPS L1, Galileo E1, SBAS L1, QZSS L1, BeiDou L1.
gnsstk::SP3NavDataFactory::useSP3clock
bool useSP3clock
Definition: SP3NavDataFactory.hpp:497
gnsstk::SP3Header
Definition: SP3Header.hpp:68
gnsstk::SP3NavDataFactory::gapIntervalClk
double gapIntervalClk
Definition: SP3NavDataFactory.hpp:454
gnsstk::RSS
T RSS(T aa, T bb, T cc)
Perform the root sum square of aa, bb and cc.
Definition: MiscMath.hpp:246
Rinex3ClockHeader.hpp
gnsstk::OrbitDataSP3::copyT
void copyT(const OrbitDataSP3 &right)
Definition: OrbitDataSP3.cpp:70
gnsstk::NavDataFactoryWithStore::numSatellites
virtual size_t numSatellites() const
Return the number of distinct signals including PRN, in the data.
Definition: NavDataFactoryWithStore.cpp:1145
gnsstk::SP3NavDataFactory::rejectBadPosFlag
bool rejectBadPosFlag
Definition: SP3NavDataFactory.hpp:501
gnsstk::SatID::system
SatelliteSystem system
System for this satellite.
Definition: SatID.hpp:156
gnsstk::SP3NavDataFactory::oidBeiDou
static const GNSSTK_EXPORT ObsID oidBeiDou
Definition: SP3NavDataFactory.hpp:69
gnsstk::CarrierBand::B2
@ B2
BeiDou B2b.
gnsstk::SP3NavDataFactory::gapIntervalPos
double gapIntervalPos
Definition: SP3NavDataFactory.hpp:444
gnsstk::OrbitDataSP3::clkDrift
double clkDrift
SV clock drift in s/s.
Definition: OrbitDataSP3.hpp:98
OrbitDataSP3.hpp
gnsstk::OrbitDataSP3::acc
Triple acc
Acceleration (m/s/s) of satellite at time.
Definition: OrbitDataSP3.hpp:94
gnsstk::NavDataFactoryWithStore::data
NavMessageMap data
Internal storage of navigation data for User searches.
Definition: NavDataFactoryWithStore.hpp:456
gnsstk::NavSignalID
Class used to identify navigation data signal types.
Definition: NavSignalID.hpp:54
gnsstk::SP3Header::baseClk
double baseClk
Definition: SP3Header.hpp:192
gnsstk::Rinex3ClockData
Definition: Rinex3ClockData.hpp:86
gnsstk::TrackingCode::L2CM
@ L2CM
Modernized GPS L2 civil M code.
gnsstk::printTime
std::string printTime(const CommonTime &t, const std::string &fmt)
Definition: TimeString.cpp:64
gnsstk::SP3NavDataFactory::ntGalileo
static const GNSSTK_EXPORT NavType ntGalileo
Definition: SP3NavDataFactory.hpp:71
gnsstk::TimeSystem::GPS
@ GPS
GPS system time.
DebugTrace.hpp
std
Definition: Angle.hpp:142
gnsstk::SP3NavDataFactory::ntGPS
static const GNSSTK_EXPORT NavType ntGPS
Generic NavTypes for each GNSS.
Definition: SP3NavDataFactory.hpp:71
gnsstk::NavMessageType
NavMessageType
Identify different types of navigation message data.
Definition: NavMessageType.hpp:59
gnsstk::TrackingCode::E5bI
@ E5bI
Galileo E5b I code.
example4.navData
navData
Definition: example4.py:15
gnsstk::OrbitDataSP3::clkDrRate
double clkDrRate
SV clock drift rate in s/s**2.
Definition: OrbitDataSP3.hpp:100
gnsstk::NavMessageType::Ephemeris
@ Ephemeris
Precision orbits for the transmitting SV.
gnsstk::SP3Data::sig
int sig[4]
the rest of the member are for version c only
Definition: SP3Data.hpp:126
gnsstk::SP3NavDataFactory::findIterator
bool findIterator(NavSatMap::iterator &sati, const CommonTime &when, NavDataPtr &navData, unsigned halfOrder, bool findEph, bool checkDataGap, bool checkInterval, double gapInterval, double maxInterval)
Definition: SP3NavDataFactory.cpp:343
gnsstk::SP3NavDataFactory::nomTimeStep
double nomTimeStep(const NavMessageID &nmid) const
Definition: SP3NavDataFactory.cpp:1439
SP3Stream.hpp
gnsstk::TrackingCode::B3I
@ B3I
BeiDou B3 I code.
gnsstk::SP3NavDataFactory::getClockInterpOrder
unsigned int getClockInterpOrder() const
Definition: SP3NavDataFactory.hpp:303
gnsstk::SP3NavDataFactory::clearClock
void clearClock()
Definition: SP3NavDataFactory.hpp:167
gnsstk::SP3NavDataFactory::ClkInterpType::Lagrange
@ Lagrange
gnsstk::OrbitDataSP3::biasSig
double biasSig
SV clock bias std deviation in microseconds.
Definition: OrbitDataSP3.hpp:97
gnsstk::NavDataFactoryWithStore::getFinalTime
CommonTime getFinalTime() const override
Definition: NavDataFactoryWithStore.hpp:173
GNSSTK_THROW
#define GNSSTK_THROW(exc)
Definition: Exception.hpp:366
DEBUGTRACE_FUNCTION
#define DEBUGTRACE_FUNCTION()
Definition: DebugTrace.hpp:117
gnsstk::OrbitDataSP3
Class for orbit information using SP3 data tables.
Definition: OrbitDataSP3.hpp:51
gnsstk::NavType::BeiDou_D2
@ BeiDou_D2
SP3NavDataFactory.hpp
gnsstk::SatelliteSystem::Glonass
@ Glonass
gnsstk::NavDataFactory::supportedSignals
NavSignalSet supportedSignals
Definition: NavDataFactory.hpp:379
gnsstk::NavDataFactoryWithStore::nearestData
NavNearMessageMap nearestData
Internal storage of navigation data for Nearest searches.
Definition: NavDataFactoryWithStore.hpp:458
gnsstk::SP3Data
Definition: SP3Data.hpp:96
gnsstk::SatelliteSystem::BeiDou
@ BeiDou
aka Compass
gnsstk::SP3NavDataFactory::storeTimeSystem
TimeSystem storeTimeSystem
Definition: SP3NavDataFactory.hpp:434
gnsstk::SP3NavDataFactory::dumpConfig
void dumpConfig(std::ostream &s) const
Definition: SP3NavDataFactory.cpp:1487
gnsstk::NavDataFactoryWithStore::offsetData
OffsetCvtMap offsetData
Definition: NavDataFactoryWithStore.hpp:461
gnsstk::NavType
NavType
Supported navigation types.
Definition: NavType.hpp:58
gnsstk::LagrangeInterpolation
T LagrangeInterpolation(const std::vector< T > &X, const std::vector< T > &Y, const T &x, T &err)
Definition: MiscMath.hpp:98
gnsstk::NavDataFactory::procNavTypes
NavMessageTypeSet procNavTypes
Definition: NavDataFactory.hpp:394
gnsstk::OrbitDataSP3::frame
RefFrame frame
Translation of coordSystem into an enum, if possible.
Definition: OrbitDataSP3.hpp:105
gnsstk::SP3NavDataFactory::halfOrderPos
unsigned halfOrderPos
Definition: SP3NavDataFactory.hpp:486
gnsstk::SP3NavDataFactory::interpolateEph
void interpolateEph(const NavMap::iterator &ti1, const NavMap::iterator &ti3, const CommonTime &when, NavDataPtr &navData)
Definition: SP3NavDataFactory.cpp:1010
gnsstk::NavDataFactoryWithStore::getInitialTime
CommonTime getInitialTime() const override
Definition: NavDataFactoryWithStore.hpp:166
gnsstk::SP3Header::timeSystem
TimeSystem timeSystem
Time system used.
Definition: SP3Header.hpp:190
gnsstk::SatelliteSystem::QZSS
@ QZSS
gnsstk::NavSatelliteID::xmitSat
SatID xmitSat
ID of the satellite transmitting the nav data.
Definition: NavSatelliteID.hpp:170
gnsstk::SP3Header::SP3c
@ SP3c
SP3 version c (contains a/b as a subset)
Definition: SP3Header.hpp:79
gnsstk::OrbitDataSP3::drRateSig
double drRateSig
Definition: OrbitDataSP3.hpp:101
gnsstk::SP3NavDataFactory::setClockLagrangeInterp
void setClockLagrangeInterp()
Definition: SP3NavDataFactory.cpp:1407
gnsstk::SP3NavDataFactory::oidQZSS
static const GNSSTK_EXPORT ObsID oidQZSS
Definition: SP3NavDataFactory.hpp:68
gnsstk::SP3NavDataFactory::ClkInterpType::Linear
@ Linear
gnsstk::NavType::GPSCNAVL5
@ GPSCNAVL5
gnsstk::TrackingCode::G3TestData
@ G3TestData
TimeString.hpp
gnsstk::SatelliteSystem::Galileo
@ Galileo
gnsstk::TrackingCode::Unknown
@ Unknown
Uninitialized value.
gnsstk::NavType::GPSCNAV2
@ GPSCNAV2
gnsstk::TrackingCode::B2I
@ B2I
BeiDou B2 I code.
gnsstk::NavType::GalFNAV
@ GalFNAV
gnsstk::NavDataFactoryWithStore::finalTime
CommonTime finalTime
Store the latest applicable orbit time here, by addNavData.
Definition: NavDataFactoryWithStore.hpp:465
gnsstk::CarrierBand::L5
@ L5
GPS L5, Galileo E5a, SBAS L5, QZSS L5, BeiDou B2a, NavIC L5.
gnsstk::CarrierBand::G2
@ G2
GLONASS G2.
gnsstk::SP3NavDataFactory::oidGalileo
static const GNSSTK_EXPORT ObsID oidGalileo
Definition: SP3NavDataFactory.hpp:68


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