Go to the documentation of this file.
56 static const std::string
dts(
"%Y/%02m/%02d %02H:%02M:%02S %3j %P");
60 const ObsID SP3NavDataFactory::oidGPS(ObservationType::NavMsg,
62 const ObsID SP3NavDataFactory::oidGalileo(ObservationType::NavMsg,
64 TrackingCode::E5aI,0,0);
65 const ObsID SP3NavDataFactory::oidQZSS(ObservationType::NavMsg,
67 const ObsID SP3NavDataFactory::oidGLONASS(ObservationType::NavMsg,
69 TrackingCode::Standard);
70 const ObsID SP3NavDataFactory::oidBeiDou(ObservationType::NavMsg,
71 CarrierBand::B1,TrackingCode::B1I,
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);
85 checkDataGapPos(false),
87 checkDataGapClk(false),
89 checkIntervalPos(false),
91 checkIntervalClk(false),
94 rejectBadPosFlag(true),
95 rejectBadClockFlag(true),
96 rejectPredPosFlag(false),
97 rejectPredClockFlag(false),
280 bool checkDataGap, checkInterval, findEph;
281 double gapInterval, maxInterval;
304 auto dataIt =
data.find(nmt);
305 if (dataIt ==
data.end())
312 auto sati = dataIt->second.find(nsid);
313 if (sati == dataIt->second.end())
319 checkDataGap, checkInterval, gapInterval,
326 for (
auto sati = dataIt->second.begin(); sati != dataIt->second.end();
329 if (sati->first != nsid)
332 checkDataGap, checkInterval, gapInterval,
345 unsigned halfOrder,
bool findEph,
346 bool checkDataGap,
bool checkInterval,
347 double gapInterval,
double maxInterval)
352 auto ti2 = sati->second.upper_bound(when);
353 auto ti1 = ti2, ti3 = ti2;
354 if (ti2 == sati->second.end())
358 DEBUGTRACE(
"probably giving up because we're at the end");
369 auto tiTmp = std::prev(ti2);
371 bool exactMatch =
false;
372 if ((tiTmp != sati->second.end()) &&
373 (tiTmp->second->timeStamp == when))
384 if (checkDataGap && (tiTmp != sati->second.end()) &&
385 ((ti2->first - tiTmp->first) > gapInterval))
387 DEBUGTRACE(
"giving up because the gap interval is too big");
402 if (
count > halfOrder+offs)
406 if ((ti1 == sati->second.end()) ||
407 ((ti3 == sati->second.end()) &&
408 (
count <= halfOrder-offs)) ||
409 ((ti1 == sati->second.begin()) &&
410 (
count <= halfOrder+offs)))
417 if (
count <= halfOrder+offs)
421 if (
count <= halfOrder-offs)
429 ti2 = std::prev(ti2);
430 if (ti2 == sati->second.end())
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))
448 DEBUGTRACE(
"giving up because the interpolation interval is too"
453 if (ti2->second->timeStamp == when)
462 navData = std::make_shared<OrbitDataSP3>(*stored);
471 DEBUGTRACE(
"interpolating ephemeris for exact match");
476 DEBUGTRACE(
"interpolating clock for exact match");
495 DEBUGTRACE(
"interpolating ephemeris for exact match (2)");
501 navOut->
copyT(*stored);
505 DEBUGTRACE(
"interpolating clock for exact match (2)");
511 DEBUGTRACE(
"found an exact match with existing data");
518 DEBUGTRACE(
"giving up, insufficient data for interpolation");
529 navData = std::make_shared<OrbitDataSP3>(*stored);
608 cerr <<
"Time system mismatch in SP3 data, "
612 <<
" (file)" << endl;
627 if ((lastSat !=
data.sat) || (lastTime !=
data.time))
629 DEBUGTRACE(
"time or satellite change, storing");
631 lastTime =
data.time;
633 if (!
store(processEph, cb, eph))
642 if (
data.RecType !=
'*')
645 (
data.x[0] == 0.0) ||
646 (
data.x[1] == 0.0) ||
683 if (!
store(processEph, cb, eph))
686 if (!
store(processClk, cb, clk))
694 catch (std::exception& exc)
697 cerr << exc.
what() << endl;
702 cerr <<
"Unknown exception" << endl;
749 cerr <<
"Time system mismatch in SP3/RINEX clock data "
753 <<
" (file)" << endl;
778 if(
data.datatype == std::string(
"AS"))
780 data.time.setTimeSystem(head.timeSystem);
782 NavDataPtr clk = std::make_shared<OrbitDataSP3>();
798 if (!
store(processClk, cb, clk))
808 catch (std::exception& exc)
811 cerr << exc.
what() << endl;
816 cerr <<
"Unknown exception" << endl;
829 return "SP3a, SP3b, SP3c, SP3d";
846 navOut = std::make_shared<OrbitDataSP3>();
855 for (
unsigned i = 0; i < 3; i++)
857 gps->
pos[i] = navIn.
x[i];
869 else if (isC && (navIn.
sig[i] >= 0))
872 DEBUGTRACE(
"pow(head.basePV,navIn.sig[" << i <<
"] = "
880 for (
unsigned i = 0; i < 3; i++)
885 gps->
vel[i] = navIn.
x[i];
888 else if (isC && (navIn.
sig[i] >= 0))
894 DEBUGTRACE(
"setting reference frame using time "
912 clkOut = std::make_shared<OrbitDataSP3>();
925 else if (isC && (navIn.
sig[3] >= 0))
934 else if (isC && (navIn.
sig[3] >= 0))
972 if (obj->validate() == expect)
995 DEBUGTRACE(
"store resetting obj ptr, use_count=" << obj.use_count());
1014 DEBUGTRACE(
"start interpolating ephemeris, distance = "
1015 << std::distance(ti1,ti3));
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);
1024 bool isExact =
false;
1029 for (
unsigned i = 0; i < 3; i++)
1039 bool haveVel =
false, haveAcc =
false;
1040 NavMap::iterator ti2;
1041 for (ti2 = ti1, idx=0; ti2 != ti3; ++ti2, ++idx)
1044 tdata[idx] = ti2->second->timeStamp - firstTime;
1045 if ((idx ==
halfOrderPos) && (ti2->second->timeStamp == when))
1051 for (
unsigned i = 0; i < 3; i++)
1054 DEBUGTRACE(posData.size() <<
" " << velData.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);
1068 double dt = when - firstTime,
err;
1072 DEBUGTRACE(setprecision(20) <<
" dt=" << dt);
1075 for (
unsigned i = 0; i < tdata.size(); i++)
1077 DEBUGTRACE(
"i=" << i <<
" times=" << tdata[i]);
1078 DEBUGTRACE(
"P=" << posData[0][i] <<
" " << posData[1][i] <<
" "
1080 DEBUGTRACE(
"V=" << velData[0][i] <<
" " << velData[1][i] <<
" "
1082 DEBUGTRACE(
"A=" << accData[0][i] <<
" " << accData[1][i] <<
" "
1086 DEBUGTRACE(
"haveVelocity=" << haveVel <<
" haveAcceleration="
1089 for (
unsigned i = 0; i < 3; i++)
1091 if (haveVel && haveAcc)
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]);
1119 <<
"]) = " << osp3->
posSig[i]);
1122 else if (haveVel && !haveAcc)
1127 osp3->
acc[i] *= 0.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]);
1150 <<
"]) = " << osp3->
posSig[i]);
1157 osp3->
vel[i] *= 10000.;
1168 <<
"]) = " << osp3->
posSig[i]);
1173 for (
unsigned i = 0; i < 3; i++)
1176 <<
" vel[" << i <<
"]=" << osp3->
vel[i]
1177 <<
" acc[" << i <<
"]=" << osp3->
acc[i]);
1188 DEBUGTRACE(
"start interpolating clock, distance = "
1189 << std::distance(ti1,ti3));
1195 CommonTime firstTime(ti1->second->timeStamp);
1200 bool isExact =
false;
1202 bool haveDrift =
false, haveDriftRate =
false;
1203 NavMap::iterator ti2;
1204 for (ti2 = ti1, idx=0; ti2 != ti3; ++ti2, ++idx)
1207 tdata[idx] = ti2->second->timeStamp - firstTime;
1208 if ((idx ==
halfOrderClk) && (ti2->second->timeStamp == when))
1217 biasSigData[idx] = nav->
biasSig;
1220 haveDrift |= (nav->
clkDrift != 0.0);
1221 haveDriftRate |= (nav->
clkDrRate != 0.0);
1223 double dt = when - firstTime,
err, slope,
1224 slopedt = tdata[Nhi]-tdata[Nlow];
1226 DEBUGTRACE(setprecision(20) <<
" dt=" << dt);
1227 gnsstk::InvalidRequest unkType(
1228 "Clock interpolation type " +
1230 " is not supported");
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]);
1252 osp3->
biasSig =
RSS(biasSigData[Nlow], biasSigData[Nhi]);
1257 osp3->
driftSig =
RSS(driftSigData[Nlow], driftSigData[Nhi]);
1269 slope = (biasData[Nhi]-biasData[Nlow]) / slopedt;
1271 osp3->
clkBias = biasData[Nlow] + slope*(dt-tdata[Nlow]);
1280 osp3->
biasSig =
RSS(biasSigData[Nlow], biasSigData[Nhi]);
1299 slope = (drRateData[Nhi]-drRateData[Nlow]) / slopedt;
1300 osp3->
clkDrRate = drRateData[Nlow] + slope*(dt-tdata[Nlow]);
1309 osp3->
drRateSig =
RSS(drRateSigData[Nlow], drRateSigData[Nhi]);
1321 osp3->
clkDrRate = (driftData[Nhi]-driftData[Nlow]) / slopedt;
1444 std::map<long,unsigned long> stepCount;
1446 std::map<unsigned long,long> countStep;
1447 if (dataIt ==
data.end())
1453 for (
const auto& sati : dataIt->second)
1455 if (sati.first != nmid)
1458 auto ti1 = sati.second.begin();
1459 auto ti2 = std::next(ti1);
1460 while (ti2 != sati.second.end())
1462 double diff = ti2->first - ti1->first;
1464 stepCount[(long)(diff*100)]++;
1472 for (
const auto& sci : stepCount)
1474 countStep[sci.second] = sci.first;
1476 DEBUGTRACE(
"countStep.empty()=" << countStep.empty());
1477 if (!countStep.empty())
1480 return countStep.begin()->second / 100.0;
1495 static const std::string fmt(
1496 "%4F %w %10.3g %4Y/%02m/%02d %2H:%02M:%02S %P");
1497 s <<
"Dump SP3NavDataFactory:" << endl
1499 <<
" bad positions." << endl
1501 <<
" bad clocks." << endl
1503 <<
" predicted positions." << endl
1505 <<
" predicted clocks." << endl
1506 <<
"Position data:" << endl
1508 <<
" (" <<
halfOrderPos <<
" points on each side)" << endl
1509 <<
" Data stored for " <<
numSatellites() <<
" satellites" << endl
1510 <<
" Time span of data: "
1515 s <<
"(there are no time limits)" << endl;
1529 s <<
" Checking for data gaps? ";
1532 s <<
"yes; gap interval is " << fixed << setprecision(2)
1539 s << endl <<
" Checking data interval? ";
1542 s <<
"yes; max interval is " << fixed << setprecision(2)
1550 <<
"Clock data:" << endl
1551 <<
" Interpolation is ";
1555 s <<
"Linear." << endl;
1565 s <<
" Checking for data gaps? ";
1568 s <<
"yes; gap interval is " << fixed << setprecision(2)
1575 s << endl <<
" Checking data interval? ";
1578 s <<
"yes; max interval is " << fixed << setprecision(2)
1586 <<
"End dump SP3NavDataFactory." << endl;
bool addDataSource(const std::string &source) override
double x[3]
The three-vector for position | velocity (m | dm/s).
std::shared_ptr< NavData > NavDataPtr
Factories instantiate these in response to find() requests.
NavType nav
Navigation message structure of this signal.
Triple posSig
Standard deviation of position.
@ Unknown
Uninitialized value.
@ Clock
SV Clock offset data. Currently only used by SP3.
bool store(bool process, NavDataFactoryCallback &cb, NavDataPtr &obj)
Class used to identify/categorize navigation message data.
void interpolateClk(const NavMap::iterator &ti1, const NavMap::iterator &ti3, const CommonTime &when, NavDataPtr &navData)
@ L1CD
Modernized GPS L1C civil code tracking (data)
double driftSig
SV clock drift std deviation in microseconds/sec.
virtual bool process(const NavDataPtr &navOut)
void setClockLinearInterp()
double getClockTimeStep(const SatID &sat) const
bool isWild() const override
Return true if any of the fields are set to match wildcards.
gnsstk::Matrix< double > L1
size_t size(void) const
Return the size of this object.
bool addRinexClock(const std::string &source, NavDataFactoryCallback &cb)
@ E1B
Galileo E1-B signal, supporting OS/HAS/SoL.
Triple vel
ECEF velocity (dm/s) of satellite at time.
static const GNSSTK_EXPORT NavType ntGLONASS
NavMessageType messageType
void copyXV(const OrbitDataSP3 &right)
Triple velSig
Standard deviation of velocity.
@ Y
Encrypted legacy GPS precise code.
static const std::string dts("%Y/%02m/%02d %02H:%02M:%02S %3j %P")
debug time string
std::string what() const
Dump to a string.
bool findGeneric(NavMessageType nmt, const NavSatelliteID &nsid, const CommonTime &when, NavDataPtr &navData)
@ Any
Used to match any carrier band.
unsigned int getPositionInterpOrder() const
Get current interpolation order for the position table.
CommonTime time
Time of epoch for this record.
@ L5I
Modernized GPS L5 civil in-phase.
@ Any
wildcard; allows comparison with any other type
std::string asString(IonexStoreStrategy e)
Convert a IonexStoreStrategy to a whitespace-free string name.
static const GNSSTK_EXPORT ObsID oidGPS
Generic ObsIDs for each GNSS.
double clkBias
SV clock bias in microseconds.
CommonTime & setTimeSystem(TimeSystem timeSystem)
Triple accSig
Standard deviation of acceleration.
static const GNSSTK_EXPORT CommonTime BEGINNING_OF_TIME
earliest representable CommonTime
static bool convertToOrbit(const SP3Header &head, const SP3Data &navIn, bool isC, NavDataPtr &navOut)
bool correlationFlag
data for optional P|V Correlation record
static const GNSSTK_EXPORT NavType ntQZSS
SVHealth
Identify different types of SV health states.
NavSearchOrder
Specify the behavior of nav data searches in NavLibrary/NavDataFactory.
std::string getFactoryFormats() const override
Return a comma-separated list of formats supported by this factory.
@ MDP
Modernized GPS military unique code.
@ Unknown
Uninitialized value.
@ Unknown
unknown time frame; for legacy code compatibility
virtual size_t count(const NavMessageID &nmid) const
ClkInterpType interpType
Clock data interpolation method.
@ Standard
Legacy Glonass civil signal.
static const GNSSTK_EXPORT ObsID oidGLONASS
@ NavMsg
Navigation Message data.
@ E5aI
Galileo E5a I code.
@ CA
Legacy GPS civil code.
CommonTime initialTime
Store the earliest applicable orbit time here, by addNavData.
static const GNSSTK_EXPORT CommonTime END_OF_TIME
latest representable CommonTime
bool find(const NavMessageID &nmid, const CommonTime &when, NavDataPtr &navOut, SVHealth xmitHealth, NavValidityType valid, NavSearchOrder order) override
char RecType
Data type indicator. P position, V velocity, * epoch.
static GNSSTK_EXPORT std::atomic< bool > enabled
If true, debugging/trace output will be printed to stderr.
ObsID obs
Carrier, tracking code, etc.
static bool setSignal(const SatID &sat, NavMessageID &signal)
SatelliteSystem system
GNSS for this signal.
static const GNSSTK_EXPORT NavType ntBeiDou
std::string coordSystem
Copy of SP3Header::coordSystem since it might not translate.
Triple pos
ECEF position (km) of satellite at time.
@ InvalidOnly
Only load/find nav messages that fail validity checks.
NavValidityType navValidity
@ ValidOnly
Only load/find nav messages that pass validity checks.
double getPositionTimeStep(const SatID &sat) const
void useRinexClockData(bool useRC=true)
static bool convertToClock(const SP3Header &head, const SP3Data &navIn, bool isC, NavDataPtr &clkOut)
ClkInterpType
Types of interpolation that can be used on the clock data.
SatID sat
ID of satellite to which the nav data applies.
double clk
The clock bias or drift for P|V (microsec|1).
void setClockInterpOrder(unsigned int order)
@ L2CML
Modernized GPS L2 civil M+L combined tracking.
const double maxBias
A clock bias >= this is considered bad.
static bool transNavMsgID(const NavMessageID &nmidIn, NavMessageID &nmidOut)
TimeSystem
Definition of various time systems.
bool process(const std::string &filename, NavDataFactoryCallback &cb) override
@ L3OCD
Glonass L3 I code.
@ L1
GPS L1, Galileo E1, SBAS L1, QZSS L1, BeiDou L1.
T RSS(T aa, T bb, T cc)
Perform the root sum square of aa, bb and cc.
void copyT(const OrbitDataSP3 &right)
virtual size_t numSatellites() const
Return the number of distinct signals including PRN, in the data.
SatelliteSystem system
System for this satellite.
static const GNSSTK_EXPORT ObsID oidBeiDou
double clkDrift
SV clock drift in s/s.
Triple acc
Acceleration (m/s/s) of satellite at time.
NavMessageMap data
Internal storage of navigation data for User searches.
Class used to identify navigation data signal types.
@ L2CM
Modernized GPS L2 civil M code.
std::string printTime(const CommonTime &t, const std::string &fmt)
static const GNSSTK_EXPORT NavType ntGalileo
static const GNSSTK_EXPORT NavType ntGPS
Generic NavTypes for each GNSS.
NavMessageType
Identify different types of navigation message data.
@ E5bI
Galileo E5b I code.
double clkDrRate
SV clock drift rate in s/s**2.
@ Ephemeris
Precision orbits for the transmitting SV.
int sig[4]
the rest of the member are for version c only
bool findIterator(NavSatMap::iterator &sati, const CommonTime &when, NavDataPtr &navData, unsigned halfOrder, bool findEph, bool checkDataGap, bool checkInterval, double gapInterval, double maxInterval)
double nomTimeStep(const NavMessageID &nmid) const
unsigned int getClockInterpOrder() const
double biasSig
SV clock bias std deviation in microseconds.
CommonTime getFinalTime() const override
#define GNSSTK_THROW(exc)
#define DEBUGTRACE_FUNCTION()
Class for orbit information using SP3 data tables.
NavSignalSet supportedSignals
NavNearMessageMap nearestData
Internal storage of navigation data for Nearest searches.
TimeSystem storeTimeSystem
void dumpConfig(std::ostream &s) const
NavType
Supported navigation types.
T LagrangeInterpolation(const std::vector< T > &X, const std::vector< T > &Y, const T &x, T &err)
NavMessageTypeSet procNavTypes
RefFrame frame
Translation of coordSystem into an enum, if possible.
void interpolateEph(const NavMap::iterator &ti1, const NavMap::iterator &ti3, const CommonTime &when, NavDataPtr &navData)
CommonTime getInitialTime() const override
SatID xmitSat
ID of the satellite transmitting the nav data.
void setClockLagrangeInterp()
static const GNSSTK_EXPORT ObsID oidQZSS
@ Unknown
Uninitialized value.
CommonTime finalTime
Store the latest applicable orbit time here, by addNavData.
@ L5
GPS L5, Galileo E5a, SBAS L5, QZSS L5, BeiDou B2a, NavIC L5.
static const GNSSTK_EXPORT ObsID oidGalileo
gnsstk
Author(s):
autogenerated on Wed Oct 25 2023 02:40:41