GLOFNavAlm.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 "GLOFNavAlm.hpp"
40 #include "TimeString.hpp"
41 #include "YDSTime.hpp"
42 #include "GLOFNavEph.hpp"
43 #include "DebugTrace.hpp"
44 
45 using namespace std;
46 
47 namespace gnsstk
48 {
49  const PZ90Ellipsoid GLOFNavAlm::ell;
50  const double GLOFNavAlm::mu = ell.gm_km();
51  const double GLOFNavAlm::ae = ell.a_km();
52  const double GLOFNavAlm::icp = 63.0 * gnsstk::PI / 180.0;
53  const double GLOFNavAlm::Tcp = 43200.0;
54  const double GLOFNavAlm::C20 = -1082.62575e-6;
55  const double GLOFNavAlm::J = (-3.0/2.0) * C20;
56  const double GLOFNavAlm::C20Term = (3.0/2.0) * C20;
57 
58 
59  GLOFNavAlm ::
60  GLOFNavAlm()
61  : healthBits(false),
62  taunA(std::numeric_limits<double>::quiet_NaN()),
63  lambdanA(std::numeric_limits<double>::quiet_NaN()),
64  deltainA(std::numeric_limits<double>::quiet_NaN()),
65  eccnA(std::numeric_limits<double>::quiet_NaN()),
66  omeganA(std::numeric_limits<double>::quiet_NaN()),
67  tLambdanA(std::numeric_limits<double>::quiet_NaN()),
68  deltaTnA(std::numeric_limits<double>::quiet_NaN()),
69  deltaTdotnA(std::numeric_limits<double>::quiet_NaN()),
70  freqnA(-1)
71  {
73  msgLenSec = 4.0;
74  }
75 
76 
77  bool GLOFNavAlm ::
78  validate() const
79  {
81  return true;
82  }
83 
84 
85  bool GLOFNavAlm ::
86  getXvt(const CommonTime& when, Xvt& xvt, const ObsID& oid)
87  {
88  bool rv = math.getXvt(when, xvt, *this);
90  return rv;
91  }
92 
93 
95  getUserTime() const
96  {
98  return mr + 2.0;
99  }
100 
101 
102  void GLOFNavAlm ::
104  {
105  // There is no stated fit interval or period of validity
106  // for almanac data. However, it is generally safe to
107  // assume that the data should not be used before
108  // the transmit time.
113  // other computed data
115  }
116 
117 
118  void GLOFNavAlm ::
119  dump(std::ostream& s, DumpDetail dl) const
120  {
121  if (dl == DumpDetail::Terse)
122  {
123  dumpTerse(s);
124  return;
125  }
126  ios::fmtflags oldFlags = s.flags();
127 
128  s.setf(ios::fixed, ios::floatfield);
129  s.setf(ios::right, ios::adjustfield);
130  s.setf(ios::uppercase);
131  s.precision(0);
132  s.fill(' ');
133 
134  s << "**************************************************************"
135  << endl
136  << " GLONASS ORB/CLK (NON-IMMEDIATE) PARAMETERS"
137  << endl
138  << endl
139  << getSignalString() << endl;
140 
141  // the rest is full details, so just return if Full is not asked for.
142  if (dl != DumpDetail::Full)
143  return;
144 
145  s.setf(ios::fixed, ios::floatfield);
146  s.setf(ios::right, ios::adjustfield);
147  s.setf(ios::uppercase);
148  s.precision(0);
149  s.fill(' ');
150 
154  CommonTime xmit(timeStamp);
156  /* ^^ */
157  string tform("%02m/%02d/%Y %03j %02H:%02M:%02S %7.0s %P");
158  s << endl
159  << " MM/DD/YYYY DOY HH:MM:SS SOD\n"
160  << "Transmit : "
161  << printTime(xmit,tform) << endl
162  << "Orbit Epoch: "
163  << printTime(Toa,tform) << endl
164  << endl
165  << "Parameter Value" << endl;
166 
167  s.setf(ios::scientific, ios::floatfield);
168  s.setf(ios::right, ios::adjustfield);
169  s.setf(ios::uppercase);
170  s.precision(6);
171  s.fill(' ');
172 
173  s << "tau " << setw(16) << taunA << " sec" << endl
174  << "lambda " << setw(16) << lambdanA << " rad" << endl
175  << "di " << setw(16) << deltainA << " rad" << endl
176  << "e " << setw(16) << eccnA << " dimensionless" << endl
177  << "omega " << setw(16) << omeganA << " rad" << endl
178  << "tLambda " << setw(16) << tLambdanA << " seconds" << endl
179  << "dT " << setw(16) << deltaTnA << " sec/orbit" << endl
180  << "dTd " << setw(16) << deltaTdotnA << " sec/orbit**2" << endl;
181 
182  s.setf(ios::fixed, ios::floatfield);
183  s.precision(0);
184  s << "C " << setw(16) << healthBits << " encoded:";
185  if (healthBits == false)
186  {
187  s << " NON-operational";
188  }
189  else
190  {
191  s << " operational";
192  }
193  s << endl
194  << "M " << setw(16) << static_cast<int>(satType)
195  << " encoded: " << StringUtils::asString(satType) << endl
196  << "H " << setw(16) << freqnA << " freq. offset" << endl
197  << "Transmit SV " << setw(16) << signal.xmitSat << endl
198  << "l " << setw(16) << lhealth
199  << " Health of transmitting SV" << endl;
200 
201  s.flags(oldFlags);
202  }
203 
204 
205  void GLOFNavAlm ::
206  dumpTerse(std::ostream& s) const
207  {
208  string tform2("%02m/%02d/%4Y %03j %02H:%02M:%02S");
209  stringstream ss;
210  ss << " " << setw(2) << signal.sat.id << " ";
211  ss << printTime(beginFit,tform2);
212  ss << " ! ";
213  ss << printTime(Toa,tform2) << " ! ";
214  if (healthBits == true)
215  {
216  ss << " op";
217  }
218  else
219  {
220  ss << "bad";
221  }
222  ss << " " << setw(2) << freqnA;
223  ss << " " << setw(2) << signal.sat.id;
224  s << ss.str();
225  }
226 
227 
228  void GLOFNavAlm ::
230  {
233  }
234 
235 
238  : lambdaBar(std::numeric_limits<double>::quiet_NaN()),
239  tau(std::numeric_limits<double>::quiet_NaN()),
240  nu(std::numeric_limits<double>::quiet_NaN()),
241  Tdeltap(std::numeric_limits<double>::quiet_NaN()),
242  n(std::numeric_limits<double>::quiet_NaN()),
243  a(std::numeric_limits<double>::quiet_NaN()),
244  i(std::numeric_limits<double>::quiet_NaN()),
245  coslambdaBar(std::numeric_limits<double>::quiet_NaN()),
246  sinlambdaBar(std::numeric_limits<double>::quiet_NaN()),
247  cos2lambdaBar(std::numeric_limits<double>::quiet_NaN()),
248  sin2lambdaBar(std::numeric_limits<double>::quiet_NaN()),
249  cos3lambdaBar(std::numeric_limits<double>::quiet_NaN()),
250  sin3lambdaBar(std::numeric_limits<double>::quiet_NaN()),
251  cos4lambdaBar(std::numeric_limits<double>::quiet_NaN()),
252  sin4lambdaBar(std::numeric_limits<double>::quiet_NaN()),
253  earthvs(std::numeric_limits<double>::quiet_NaN()),
254  sini(std::numeric_limits<double>::quiet_NaN()),
255  sini2(std::numeric_limits<double>::quiet_NaN()),
256  cosi(std::numeric_limits<double>::quiet_NaN()),
257  cosi2(std::numeric_limits<double>::quiet_NaN()),
258  JTerm(std::numeric_limits<double>::quiet_NaN()),
259  JsinTerm(std::numeric_limits<double>::quiet_NaN()),
260  Jsini2Term(std::numeric_limits<double>::quiet_NaN()),
261  Jcosi2Term(std::numeric_limits<double>::quiet_NaN()),
262  h(std::numeric_limits<double>::quiet_NaN()),
263  l(std::numeric_limits<double>::quiet_NaN()),
264  ecc2(std::numeric_limits<double>::quiet_NaN()),
265  ecc2obv(std::numeric_limits<double>::quiet_NaN())
266  {
267  }
268 
269 
271  setEccArgOfPerigee(double ecc, double omega)
272  {
274  h = ecc * std::sin(omega);
275  l = ecc * std::cos(omega);
276  ecc2 = ecc * ecc;
277  ecc2obv = 1.0 - ecc2;
278  DEBUGTRACE("ecc = " << ecc);
279  DEBUGTRACE("omega = " << omega);
280  DEBUGTRACE("h = " << h);
281  DEBUGTRACE("l = " << l);
282  DEBUGTRACE("ecc2 = " << ecc2);
283  DEBUGTRACE("ecc2obv = " << ecc2obv);
284  }
285 
286 
288  setSemiMajorAxisIncl(double deltaT, double deltai, double omega, double ecc)
289  {
291  DEBUGTRACE("deltaT = " << deltaT);
292  DEBUGTRACE("deltai = " << deltai);
293  DEBUGTRACE("omega = " << omega);
294  DEBUGTRACE("ecc = " << ecc);
295  // from GLONASS ICD appendix 3.2.2, Algorithm of calculation
296  double aCurr = -9999999999999, aPrev = -9999999999999;
297  setEccArgOfPerigee(ecc, omega);
298  Tdeltap = Tcp + deltaT;
299  n = 2.0*gnsstk::PI / Tdeltap;
300  i = icp + deltai;
301  sini = sin(i);
302  sini2 = sini * sini;
303  cosi = std::cos(i);
304  cosi2 = cosi * cosi;
305  double ninv = Tdeltap / (2.0*gnsstk::PI);
306  DEBUGTRACE(setprecision(15) << "icp = " << icp);
307  DEBUGTRACE("Delta i = " << deltai);
308  DEBUGTRACE("i = " << i);
309  DEBUGTRACE("sini2 = " << sini2);
310  DEBUGTRACE("ninv = " << ninv);
311  DEBUGTRACE("mu = " << mu);
312  DEBUGTRACE("ecc2obv = " << ecc2obv);
313  nu = -omega;
314  double nuTerm = std::pow(1.0 + ecc * cos(nu), 3.0);
315  double omegaTerm = std::pow(1.0 + ecc * cos(omega), 2.0);
316  double eTerm = std::pow(ecc2obv, 3.0/2.0);
317  double siniTerm = (2.0 - (5.0/2.0)*sini2);
318  double bigTerm =
319  (siniTerm * (eTerm / omegaTerm) + (nuTerm / ecc2obv));
320  DEBUGTRACE("bigTerm = " << siniTerm << " * (" << eTerm << " / "
321  << omegaTerm << ") + (" << nuTerm << " / " << ecc2obv << ")");
322  // initial approximation a^(0)
323  aPrev = std::pow(ninv * ninv * mu, 1.0/3.0);
324  DEBUGTRACE("a^(0) = " << aPrev);
325  DEBUGTRACE("Tock_b = " << nuTerm);
326  DEBUGTRACE("Tock_c = " << (nuTerm / ecc2obv));
327  DEBUGTRACE("Tock_d = " << eTerm);
328  DEBUGTRACE("Tock_e = " << C20Term);
329  DEBUGTRACE("Tock_f = " << omegaTerm);
330  DEBUGTRACE("Tock_g = " << (eTerm / omegaTerm));
331  DEBUGTRACE("Tock_h = " << siniTerm);
332  DEBUGTRACE("Tock_i = " << bigTerm);
333  unsigned iteration = 0;
334  while (fabs(aCurr-aPrev) >= 1e-3)
335  {
336  double pn = aPrev * ecc2obv;
337  // note that I use Tdeltap / .... to match Tdeltap * ....^-1
338  double tock_k = (1.0 + C20Term * (ae/pn) * (ae/pn) * bigTerm);
339  double Tock = Tdeltap / tock_k;
340  DEBUGTRACE("Tock_k = " << tock_k);
341  DEBUGTRACE("p(" << iteration << ") = " << pn);
342  DEBUGTRACE("Tock(" << (iteration+1) << ") = " << Tock);
343  if (iteration > 0)
344  aPrev = aCurr;
345  aCurr = std::pow(std::pow(Tock/(2.0*gnsstk::PI),2.0) * mu, 1.0/3.0);
346  DEBUGTRACE("a^(" << iteration << ") = " << aCurr);
347  DEBUGTRACE("diff = " << fabs(aCurr-aPrev));
348  iteration++;
349  }
350  DEBUGTRACE("a = " << aCurr << " km");
351  a = aCurr;
352  earthvs = std::pow(ae/a, 2.0);
353  JTerm = J * earthvs;
354  JsinTerm = JTerm * (1.0-(3.0/2.0)*sini2);
355  Jsini2Term = JTerm * sini2;
356  Jcosi2Term = JTerm * cosi2;
357  }
358 
359 
361  setLambdaBar(double M, double omega, double tau, double n)
362  {
364  lambdaBar = M + omega + n * tau;
365  DEBUGTRACE("M = " << M);
366  DEBUGTRACE("omega = " << omega);
367  DEBUGTRACE("n = " << n);
368  DEBUGTRACE("tau = " << tau);
369  DEBUGTRACE("n*tau = " << (n*tau));
370  DEBUGTRACE("lambdaBar = " << lambdaBar);
371  coslambdaBar = std::cos(lambdaBar);
372  sinlambdaBar = std::sin(lambdaBar);
373  cos2lambdaBar = std::cos(2.0*lambdaBar);
374  sin2lambdaBar = std::sin(2.0*lambdaBar);
375  cos3lambdaBar = std::cos(3.0*lambdaBar);
376  sin3lambdaBar = std::sin(3.0*lambdaBar);
377  cos4lambdaBar = std::cos(4.0*lambdaBar);
378  sin4lambdaBar = std::sin(4.0*lambdaBar);
379  }
380 
381 
383  setDeltas(double M, double omega, double a, double dt)
384  {
386  DEBUGTRACE("M = " << M);
387  DEBUGTRACE("omega = " << omega);
388  DEBUGTRACE("a = " << a);
389  DEBUGTRACE("dt = " << dt);
390  Deltas m1, m2;
391  // lambda Bar MUST be set just prior to calling setDeltas in
392  // order to get the proper value for tau, and thus the proper
393  // values for lambdaBar and derived values in place.
394  setLambdaBar(M, omega, 0, n);
395  m1.setDeltas(*this, a, 0, n); // tau is 0 for m=1
396  setLambdaBar(M, omega, dt, n);
397  m2.setDeltas(*this, a, dt, n);
398  deltas = m2 - m1;
399  DEBUGTRACE("deltas:");
400  DEBUGTRACE("delta a = " << deltas.deltaa);
401  DEBUGTRACE("delta h = " << deltas.deltah);
402  DEBUGTRACE("delta l = " << deltas.deltal);
403  DEBUGTRACE("delta OMEGA = " << deltas.deltaOMEGA);
404  DEBUGTRACE("delta i = " << deltas.deltai);
405  DEBUGTRACE("delta lambda* = " << deltas.deltalambdaBar);
406  }
407 
408 
410  getomegai(double hi, double li, double epsi)
411  {
413  if (epsi == 0)
414  {
415  return 0;
416  }
417  else if (li != 0)
418  {
419  return std::atan(hi/li);
420  }
421  else if (hi == epsi)
422  {
423  return gnsstk::PI/2.0;
424  }
425  else if (hi == -epsi)
426  {
427  return -gnsstk::PI/2.0;
428  }
429  // The above conditions match everything in the ICD, but I
430  // can't help but wonder if epsi and hi will ever not match
431  // at all and still be non-zero, so I'm sticking this here
432  // just in case.
433  AssertionFailure exc("omega_i conditions not met");
434  GNSSTK_THROW(exc);
435  }
436 
437 
439  integrateEin(double Mi, double epsi)
440  {
442  double Ein = Mi, lastEin = -99999;
443  while (fabs(Ein-lastEin) >= 1e-8)
444  {
445  lastEin = Ein;
446  Ein = Mi + epsi * std::sin(lastEin);
447  }
448  return Ein;
449  }
450 
451 
453  getXvt(const CommonTime& when, Xvt& xvt, const GLOFNavAlm& alm)
454  {
456  // expressions computed once and reused multiple times are
457  // marked "optimize"
458  // I think this is sufficient - the original formula appears
459  // to be getting the time difference between the requested
460  // and reference times, in seconds.
461  // This may also be the only place where NA is implicitly used.
462  DEBUGTRACE("when = " << printTime(when, "%Y/%02m/%02d %02H:%02M:%05.2f"));
463  DEBUGTRACE("toa = " << printTime(alm.Toa, "%Y/%02m/%02d %02H:%02M:%05.2f"));
464  double tstar = when - alm.Toa;
465  double Wk = tstar / Tdeltap;
466  // I'm definitely not sure about this one.
467  double W;
468  std::modf(Wk,&W); // W is the integer part of Wk
469  double tscale = Tdeltap*W + alm.deltaTdotnA*W*W; // optimize
470  double tLambdakBar = alm.tLambdanA + tscale;
471  double tLambdak = std::fmod(tLambdakBar, 86400.0);
472  double OMEGAdot = C20Term * n * earthvs * cosi * std::sqrt(ecc2obv);
473  double lambdak = alm.lambdanA + (OMEGAdot - omega3) * tscale;
474  DEBUGTRACE("tstar = " << tstar);
475  DEBUGTRACE("Wk = " << Wk);
476  DEBUGTRACE("W = " << W);
477  DEBUGTRACE("tlambdakBar = " << tLambdakBar);
478  DEBUGTRACE("tlambdak = " << tLambdak);
479  DEBUGTRACE("n = " << n);
480  DEBUGTRACE("OMEGAdot = " << OMEGAdot);
481  DEBUGTRACE("lambdak = " << lambdak);
482  double gst = GLOFNavEph::getSiderealTime(when);
483  DEBUGTRACE("gst = " << gst);
484  double S0 = gst*PI/12.0;
485  DEBUGTRACE("S0 = " << S0);
486  double S = S0 + omega3 * (tLambdak - 10800);
487  double OMEGA = lambdak + S;
488  DEBUGTRACE("OMEGA = " << OMEGA);
489  DEBUGTRACE("S = " << S);
490  DEBUGTRACE("S0 = " << S0);
491  DEBUGTRACE("C20Term = " << C20Term);
492  DEBUGTRACE("earthvs = " << earthvs);
493  DEBUGTRACE("ecc2obv = " << ecc2obv);
495  double tanEdiv2 = std::sqrt((1.0-alm.eccnA)/(1.0+alm.eccnA)) *
496  std::tan(nu/2.0);
497  double E = 2.0 * std::atan(tanEdiv2);
498  double M = E - alm.eccnA * std::sin(E);
499  DEBUGTRACE("tan(E/2) = " << tanEdiv2);
500  DEBUGTRACE("E = " << E);
501  DEBUGTRACE("M = " << M);
502  setDeltas(M, alm.omeganA, a, tstar);
504  double ai = a + deltas.deltaa;
505  double hi = h + deltas.deltah;
506  double li = l + deltas.deltal;
507  double ii = i + deltas.deltai;
508  DEBUGTRACE("OMEGA = " << OMEGA);
509  DEBUGTRACE("deltaOMEGA = " << deltas.deltaOMEGA);
510  double OMEGAi = OMEGA + deltas.deltaOMEGA;
511  double sinOMEGAi = std::sin(OMEGAi);
512  double cosOMEGAi = std::cos(OMEGAi);
513  double epsi = std::sqrt(hi*hi+li*li);
514  double omegai = getomegai(hi, li, epsi);
515  double lambdaStar = M + alm.omeganA + n*tstar + deltas.deltalambdaBar;
516  double Mi = lambdaStar - omegai;
517  double Ein = integrateEin(Mi, epsi);
518  double tannuidiv2 = std::sqrt((1.0+epsi)/(1.0-epsi)) * std::tan(Ein/2.0);
519  double nui = 2.0 * std::atan(tannuidiv2);
520  double sinnui = std::sin(nui);
521  double cosnui = std::cos(nui);
522  double cosii = std::cos(ii);
523  double sinii = std::sin(ii);
524  double muTerm = std::sqrt(mu/ai);
525  double epsiTerm = std::sqrt(1-(epsi*epsi));
526  double ui = nui + omegai;
527  double cosui = std::cos(ui);
528  double sinui = std::sin(ui);
529  double ri = ai * (1-(epsi * cos(Ein)));
530  double Vri = muTerm * ((epsi * sinnui) / epsiTerm);
531  double Vui = muTerm * ((1 + epsi * cosnui) / epsiTerm);
532  DEBUGTRACE("hi = " << hi);
533  DEBUGTRACE("li = " << li);
534  DEBUGTRACE("epsi = " << epsi);
535  DEBUGTRACE("omegai = " << omegai);
536  DEBUGTRACE("ai = " << ai);
537  DEBUGTRACE("ii = " << ii);
538  DEBUGTRACE("OMEGAi = " << OMEGAi);
539  DEBUGTRACE("Mi = " << Mi);
540  DEBUGTRACE("lambda* = " << lambdaStar);
541  DEBUGTRACE("Ein = " << Ein);
542  DEBUGTRACE("nui = " << nui);
543  DEBUGTRACE("ui = " << ui);
544  DEBUGTRACE("ri = " << ri);
545  DEBUGTRACE("Vri = " << Vri);
546  DEBUGTRACE("Vui = " << Vui);
547  xvt.x[0] = ri * ((cosui*cosOMEGAi) - (sinui*sinOMEGAi*cosii));
548  xvt.x[1] = ri * ((cosui*sinOMEGAi) + (sinui*cosOMEGAi*cosii));
549  xvt.x[2] = ri * sinui * sinii;
550  // change km to m
551  xvt.x[0] *= 1000.0;
552  xvt.x[1] *= 1000.0;
553  xvt.x[2] *= 1000.0;
554 
555  DEBUGTRACE(" sin cos");
556  DEBUGTRACE("ii " << sinii << " " << cosii);
557  DEBUGTRACE("ui " << sinui << " " << cosui);
558  DEBUGTRACE("OMEGAi " << sinOMEGAi << " " << cosOMEGAi);
559  xvt.v[0] = Vri * (cosui*cosOMEGAi - sinui*sinOMEGAi*cosii) -
560  Vui * (sinui*cosOMEGAi + cosui*sinOMEGAi*cosii);
561  xvt.v[1] = Vri * (cosui*sinOMEGAi + sinui*cosOMEGAi*cosii) -
562  Vui * (sinui*sinOMEGAi - cosui*cosOMEGAi*cosii);
563  /* debugging code
564  double vyaa = (cosui*sinOMEGAi);
565  double vyab = (sinui*cosOMEGAi*cosii);
566  double vya = Vri * (vyaa + vyab);
567  double vyba = (sinui*sinOMEGAi);
568  double vybb = (-cosui*cosOMEGAi*cosii);
569  double vyb = -Vui * (vyba + vybb);
570  DEBUGTRACE("vyaa = " << vyaa);
571  DEBUGTRACE("vyab = " << vyab);
572  DEBUGTRACE("vya = " << vya);
573  DEBUGTRACE("vyba = " << vyba);
574  DEBUGTRACE("vybb = " << vybb);
575  DEBUGTRACE("vyb = " << vyb);
576  */
577  xvt.v[2] = Vri * sinui * sinii + Vui * cosui * sinii;
578  // change km/s to m/s
579  xvt.v[0] *= 1000.0;
580  xvt.v[1] *= 1000.0;
581  xvt.v[2] *= 1000.0;
582  xvt.frame = RefFrame(RefFrameSys::PZ90, when);
583  // clock bias and drift are not available (?).
585  return true;
586  }
587 
588 
591  : deltaa(std::numeric_limits<double>::quiet_NaN()),
592  deltah(std::numeric_limits<double>::quiet_NaN()),
593  deltal(std::numeric_limits<double>::quiet_NaN()),
594  deltaOMEGA(std::numeric_limits<double>::quiet_NaN()),
595  deltai(std::numeric_limits<double>::quiet_NaN()),
596  deltalambdaBar(std::numeric_limits<double>::quiet_NaN())
597  {
598  }
599 
600 
602  operator-(const Deltas& right) const
603  {
604  Deltas rv;
605  rv.deltaa = deltaa-right.deltaa;
606  rv.deltah = deltah-right.deltah;
607  rv.deltal = deltal-right.deltal;
608  rv.deltaOMEGA = deltaOMEGA-right.deltaOMEGA;
609  rv.deltai = deltai-right.deltai;
610  // the ICD actually writes this ONE FORMULA as
611  // delta lambda * = delta lambda bar (2) - delta lambda bar (1)
612  // so it's not strictly accuracte to call it lambdaBar after
613  // subtracting, I guess, but whatever.
614  rv.deltalambdaBar = deltalambdaBar-right.deltalambdaBar;
615  return rv;
616  }
617 
618 
620  setDeltas(const NumberCruncher& math, double a, double tau, double n)
621  {
623  // fractions used repeatedly.
624  static constexpr double OH = 0.5; // one half
625  static constexpr double TH = 3.0/2.0; // three halves
626  static constexpr double FH = 5.0/2.0; // five halves
627  static constexpr double SH = 7.0/2.0; // seven halves
628  static constexpr double STH = 17.0/2.0; // seventeen halves
629  static constexpr double ST = 7.0/3.0; // seven thirds
630  static constexpr double OQ = 1.0/4.0; // one quarter
631  static constexpr double SQ = 7.0/4.0; // seven quarters
632  static constexpr double SS = 7.0/6.0; // seven sixths
633  static constexpr double STF = 7.0/24.0;// seven twenty-fourths
634  static constexpr double FNSS = 49.0/72.0; // guess.
635  // note that lambda bar is defined in two different ways, one
636  // without adding n*tau, and one with, where the latter is
637  // used when computing corrections due to effects of C20.
638  double a_a = 2.0 * math.JsinTerm * (math.l * math.coslambdaBar
639  + math.h * math.sinlambdaBar)
640  + math.Jsini2Term * (OH * math.h * math.sinlambdaBar
641  - OH * math.l * math.coslambdaBar
643  + SH * math.l * math.cos3lambdaBar
644  + SH * math.h * math.sin3lambdaBar);
645  // The ICD defines the abbove expression as delta a(m) / a,
646  // so multiply the whole thing by a to get delta a(m)
647  deltaa = a_a * a;
648  deltah = math.JsinTerm * (math.l * n * tau
650  + TH * math.l * math.sin2lambdaBar
651  - TH * math.h * math.cos2lambdaBar)
652  - OQ * math.Jsini2Term * (math.sinlambdaBar
653  - ST * math.sin3lambdaBar
654  + 5.0 * math.l * math.sin2lambdaBar
655  - STH * math.l * math.sin4lambdaBar
656  + STH * math.h * math.cos4lambdaBar
657  + math.h * math.cos2lambdaBar)
658  + math.Jcosi2Term * (math.l * n * tau
659  - OH * math.l * math.sin2lambdaBar);
660  deltal = math.JsinTerm * (-math.h * n * tau
662  + TH * math.l * math.cos2lambdaBar
663  + TH * math.h * math.sin2lambdaBar)
664  - OQ * math.Jsini2Term * (-math.coslambdaBar
665  - ST*math.cos3lambdaBar
666  - 5.0 * math.h * math.sin2lambdaBar
667  - STH * math.l * math.cos4lambdaBar
668  - STH * math.h * math.sin4lambdaBar
669  + math.l * math.cos2lambdaBar)
670  + math.Jcosi2Term * (-math.h * n * tau
671  + OH * math.h * math.sin2lambdaBar);
672  deltaOMEGA = -math.JTerm * math.cosi * (n * tau
673  + SH * math.l * math.sinlambdaBar
674  - FH * math.h * math.coslambdaBar
675  - OH * math.sin2lambdaBar
676  - SS * math.l * math.sin3lambdaBar
677  + SS * math.h * math.cos3lambdaBar);
678  deltai = OH * math.JTerm * math.sini * math.cosi *
679  (-math.l * math.coslambdaBar
680  + math.h * math.sinlambdaBar
682  + ST * math.l * math.cos3lambdaBar
683  + ST * math.h * math.sin3lambdaBar);
684  deltalambdaBar = (2.0 * math.JsinTerm * (n * tau
685  + SQ * math.l * math.sinlambdaBar
686  - SQ * math.h * math.coslambdaBar))
687  + (3.0 * math.Jsini2Term * (-STF * math.h * math.coslambdaBar
688  - STF * math.l * math.sinlambdaBar
689  - FNSS * math.h * math.cos3lambdaBar
690  + FNSS * math.l * math.sin3lambdaBar
691  + OQ * math.sin2lambdaBar))
692  + (math.Jcosi2Term * (n * tau
693  + SH * math.l * math.sinlambdaBar
694  - FH * math.h * math.coslambdaBar
695  - OH * math.sin2lambdaBar
696  - SS * math.l * math.sin3lambdaBar
697  + SS * math.h * math.cos3lambdaBar));
698 /* Unused code, unknown purpose.
699  double K81 = (2.0 * math.JsinTerm * (n * tau +
700  SQ * math.l * math.sinlambdaBar -
701  SQ * math.h * math.coslambdaBar));
702  double Q81 = (3.0 * math.Jsini2Term * (-STF * math.h * math.coslambdaBar -
703  STF * math.l * math.sinlambdaBar -
704  FNSS * math.h * math.cos3lambdaBar +
705  FNSS * math.l * math.sin3lambdaBar +
706  OQ * math.sin2lambdaBar));
707  double W81 = (math.Jcosi2Term * (n * tau
708  + SH * math.l * math.sinlambdaBar
709  - FH * math.h * math.coslambdaBar
710  - OH * math.sin2lambdaBar
711  - SS * math.l * math.sin3lambdaBar
712  + SS * math.h * math.cos3lambdaBar));
713 */
714  int m = (tau == 0) ? 1 : 2;
715  DEBUGTRACE("deltaa(m=" << m << ")/a = " << a_a);
716  DEBUGTRACE("deltah(m=" << m << ") = " << deltah);
717  DEBUGTRACE("deltal(m=" << m << ") = " << deltal);
718  DEBUGTRACE("deltaOMEGA(m=" << m << ") = " << deltaOMEGA);
719  DEBUGTRACE("deltai(m=" << m << ") = " << deltai);
720  DEBUGTRACE("deltalambdaBar(m=" << m << ") = " << deltalambdaBar);
721  DEBUGTRACE("lambdaBar(m=" << m << ") = " << math.lambdaBar);
722  DEBUGTRACE("h(m=" << m << ") = " << math.h);
723  DEBUGTRACE("l(m=" << m << ") = " << math.l);
724  DEBUGTRACE("tau(m=" << m << ") = " << tau);
725  DEBUGTRACE("J(m=" << m << ") = " << J);
726  DEBUGTRACE("e^2(m=" << m << ") = " << math.ecc2);
727  DEBUGTRACE("1-e^2(m=" << m << ") = " << math.ecc2obv);
728  DEBUGTRACE("JTerm(m=" << m << ") = " << math.JTerm);
729  DEBUGTRACE("JsinTerm(m=" << m << ") = " << math.JsinTerm);
730  DEBUGTRACE("a(m=" << m << ") = " << a);
731  }
732 }
gnsstk::GLOFNavAlm::NumberCruncher::tau
double tau
Definition: GLOFNavAlm.hpp:239
gnsstk::GLOFNavAlm::math
NumberCruncher math
Retain as much computed data as possible.
Definition: GLOFNavAlm.hpp:292
YDSTime.hpp
gnsstk::GLOFNavAlm::NumberCruncher::Deltas::deltalambdaBar
double deltalambdaBar
Definition: GLOFNavAlm.hpp:230
gnsstk::GLOFNavAlm::NumberCruncher::Deltas::deltai
double deltai
Definition: GLOFNavAlm.hpp:229
gnsstk::RefFrameSys::PZ90
@ PZ90
The reference frame used by Glonass.
gnsstk::GLOFNavAlm::NumberCruncher::Deltas::deltah
double deltah
Definition: GLOFNavAlm.hpp:226
gnsstk::NavData::getSignalString
std::string getSignalString() const
Definition: NavData.cpp:86
gnsstk::GLOFNavAlm::deltaTnA
double deltaTnA
Correction to mean value of Draconian period (Delta T_n^A).
Definition: GLOFNavAlm.hpp:285
gnsstk::GLOFNavEph::getSiderealTime
static double getSiderealTime(const CommonTime &time)
Definition: GLOFNavEph.cpp:397
gnsstk::GLOFNavAlm::NumberCruncher::ecc2
double ecc2
ecc**2
Definition: GLOFNavAlm.hpp:264
gnsstk::NavData::msgLenSec
double msgLenSec
Definition: NavData.hpp:199
gnsstk::GLOFNavAlm::NumberCruncher::sin3lambdaBar
double sin3lambdaBar
sin(3*lambdaBar)
Definition: GLOFNavAlm.hpp:250
gnsstk::SatID::id
int id
Satellite identifier, e.g. PRN.
Definition: SatID.hpp:154
gnsstk::GLOFNavAlm::NumberCruncher::setLambdaBar
void setLambdaBar(double M, double omega, double tau, double n)
Definition: GLOFNavAlm.cpp:361
gnsstk::GLOFNavAlm::Tcp
static const GNSSTK_EXPORT double Tcp
Tcp</cp> as defined in GLONASS ICD appendix 3.2.1.
Definition: GLOFNavAlm.hpp:69
gnsstk::GLOFNavAlm::NumberCruncher::ecc2obv
double ecc2obv
1-ecc**2
Definition: GLOFNavAlm.hpp:265
gnsstk::GLOFNavAlm::NumberCruncher::JTerm
double JTerm
J * earthvs.
Definition: GLOFNavAlm.hpp:258
gnsstk::GLOFNavAlm::NumberCruncher::NumberCruncher
NumberCruncher()
Initialize stuff to NaN.
Definition: GLOFNavAlm.cpp:237
gnsstk::GLOFNavAlm::NumberCruncher::cos4lambdaBar
double cos4lambdaBar
cos(4*lambdaBar)
Definition: GLOFNavAlm.hpp:251
gnsstk::GLOFNavAlm::NumberCruncher::n
double n
2pi/Tdeltap.
Definition: GLOFNavAlm.hpp:242
gnsstk::GLOFNavAlm::NumberCruncher::getomegai
static double getomegai(double hi, double li, double epsi)
Definition: GLOFNavAlm.cpp:410
gnsstk::GLOFNavAlm::lambdanA
double lambdanA
Longitude of ascending node (lambda_n^A).
Definition: GLOFNavAlm.hpp:280
gnsstk::Xvt::Healthy
@ Healthy
Satellite is healthy, PVT valid.
Definition: Xvt.hpp:96
gnsstk::NavMessageID::messageType
NavMessageType messageType
Definition: NavMessageID.hpp:97
gnsstk::GLOFNavAlm::NumberCruncher::sinlambdaBar
double sinlambdaBar
sin(lambdaBar)
Definition: GLOFNavAlm.hpp:246
gnsstk::max
T max(const SparseMatrix< T > &SM)
Maximum element - return 0 if empty.
Definition: SparseMatrix.hpp:881
DEBUGTRACE
#define DEBUGTRACE(EXPR)
Definition: DebugTrace.hpp:119
gnsstk::GLOFNavAlm::Toa
CommonTime Toa
Reference time for almanac.
Definition: GLOFNavAlm.hpp:275
example5.oid
oid
Definition: example5.py:29
gnsstk::Xvt::frame
RefFrame frame
reference frame of this data
Definition: Xvt.hpp:156
gnsstk::NavFit::endFit
CommonTime endFit
Time at end of fit interval.
Definition: NavFit.hpp:55
gnsstk::GLOFNavAlm::eccnA
double eccnA
Eccentricity (epsilon_n^A).
Definition: GLOFNavAlm.hpp:282
gnsstk::StringUtils::asString
std::string asString(IonexStoreStrategy e)
Convert a IonexStoreStrategy to a whitespace-free string name.
Definition: IonexStoreStrategy.cpp:46
gnsstk::GLOFNavAlm::NumberCruncher::l
double l
Definition: GLOFNavAlm.hpp:263
gnsstk::CommonTime::setTimeSystem
CommonTime & setTimeSystem(TimeSystem timeSystem)
Definition: CommonTime.hpp:195
gnsstk::GLOFNavAlm::NumberCruncher::h
double h
Definition: GLOFNavAlm.hpp:262
gnsstk::PI
const double PI
GPS value of PI; also specified by GAL.
Definition: GNSSconstants.hpp:62
gnsstk::Xvt::v
Triple v
satellite velocity in ECEF Cartesian, meters/second
Definition: Xvt.hpp:152
gnsstk::GLOFNavAlm::NumberCruncher::Deltas
Definition: GLOFNavAlm.hpp:207
gnsstk::GLOFNavAlm::NumberCruncher::setSemiMajorAxisIncl
void setSemiMajorAxisIncl(double deltaT, double deltai, double omega, double ecc)
Definition: GLOFNavAlm.cpp:288
gnsstk::RefFrame
Definition: RefFrame.hpp:53
gnsstk::NavData::signal
NavMessageID signal
Source signal identification for this navigation message data.
Definition: NavData.hpp:175
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::GLOFNavAlm::NumberCruncher::sini
double sini
sin(i)
Definition: GLOFNavAlm.hpp:254
gnsstk::GLOFNavAlm::NumberCruncher::setDeltas
void setDeltas(double M, double omega, double a, double dt)
Definition: GLOFNavAlm.cpp:383
gnsstk::GLOFNavAlm::NumberCruncher::Deltas::deltal
double deltal
Definition: GLOFNavAlm.hpp:227
std::sin
double sin(gnsstk::Angle x)
Definition: Angle.hpp:144
gnsstk::Xvt::relcorr
double relcorr
relativity correction (standard 2R.V/c^2 term), seconds
Definition: Xvt.hpp:155
gnsstk::GLOFNavAlm::getUserTime
CommonTime getUserTime() const override
Definition: GLOFNavAlm.cpp:95
gnsstk::GLOFNavAlm::omeganA
double omeganA
Argument of perigee (omega_n^A).
Definition: GLOFNavAlm.hpp:283
gnsstk::NavData::timeStamp
CommonTime timeStamp
Definition: NavData.hpp:173
gnsstk::GLOFNavAlm
Definition: GLOFNavAlm.hpp:53
gnsstk::CommonTime::END_OF_TIME
static const GNSSTK_EXPORT CommonTime END_OF_TIME
latest representable CommonTime
Definition: CommonTime.hpp:104
gnsstk::GLOFNavAlm::omega3
static constexpr GNSSTK_EXPORT double omega3
Definition: GLOFNavAlm.hpp:65
gnsstk::GLOFNavAlm::NumberCruncher::Deltas::operator-
Deltas operator-(const Deltas &right) const
Definition: GLOFNavAlm.cpp:602
gnsstk::Xvt::x
Triple x
Sat position ECEF Cartesian (X,Y,Z) meters.
Definition: Xvt.hpp:151
gnsstk::GLOFNavAlm::deltaTdotnA
double deltaTdotnA
Time derivative of deltaT (Delta T'_n^A).
Definition: GLOFNavAlm.hpp:286
gnsstk::GLOFNavAlm::NumberCruncher::integrateEin
static double integrateEin(double Mi, double epsi)
Definition: GLOFNavAlm.cpp:439
gnsstk::GLOFNavAlm::NumberCruncher::sin2lambdaBar
double sin2lambdaBar
sin(2*lambdaBar)
Definition: GLOFNavAlm.hpp:248
gnsstk::GLOFNavAlm::NumberCruncher::cos3lambdaBar
double cos3lambdaBar
cos(3*lambdaBar)
Definition: GLOFNavAlm.hpp:249
gnsstk::GLOFNavAlm::validate
bool validate() const override
Definition: GLOFNavAlm.cpp:78
gnsstk::ObsID
Definition: ObsID.hpp:82
gnsstk::GLOFNavAlm::NumberCruncher::getXvt
bool getXvt(const CommonTime &when, Xvt &xvt, const GLOFNavAlm &alm)
Definition: GLOFNavAlm.cpp:453
gnsstk::GLOFNavAlm::taunA
double taunA
Time offset to GLONASS time (tau_n^A).
Definition: GLOFNavAlm.hpp:279
gnsstk::NavSatelliteID::sat
SatID sat
ID of satellite to which the nav data applies.
Definition: NavSatelliteID.hpp:169
gnsstk::CommonTime
Definition: CommonTime.hpp:84
gnsstk::GLOFNavAlm::NumberCruncher::setEccArgOfPerigee
void setEccArgOfPerigee(double ecc, double omega)
Definition: GLOFNavAlm.cpp:271
gnsstk::GLOFNavAlm::icp
static const GNSSTK_EXPORT double icp
icp</cp> as defined in GLONASS ICD appendix 3.2.1
Definition: GLOFNavAlm.hpp:67
gnsstk::GLOFNavAlm::healthBits
bool healthBits
Health flag (C_n, 1 = operable).
Definition: GLOFNavAlm.hpp:276
gnsstk::NavFit::beginFit
CommonTime beginFit
Time at beginning of fit interval.
Definition: NavFit.hpp:54
gnsstk::Xvt
Definition: Xvt.hpp:60
gnsstk::GLOFNavData::lhealth
bool lhealth
Health flag? Different from B_n and C_n?
Definition: GLOFNavData.hpp:70
std::cos
double cos(gnsstk::Angle x)
Definition: Angle.hpp:146
gnsstk::GLOFNavAlm::NumberCruncher::lambdaBar
double lambdaBar
Definition: GLOFNavAlm.hpp:238
gnsstk::GLOFNavAlm::setSemiMajorAxisIncl
void setSemiMajorAxisIncl()
Compute and set the semi-major axis (A) and inclination (i).
Definition: GLOFNavAlm.cpp:229
gnsstk::DumpDetail::Full
@ Full
Include all detailed information.
gnsstk::TimeSystem::GLO
@ GLO
GLONASS system time (aka UTC(SU))
gnsstk::GLOFNavAlm::NumberCruncher::Jcosi2Term
double Jcosi2Term
JTerm * sini2.
Definition: GLOFNavAlm.hpp:261
gnsstk::GLOFNavData::xmit2
CommonTime xmit2
Transmit time for string 2 (eph) or odd string.
Definition: GLOFNavData.hpp:67
gnsstk::GLOFNavAlm::fixFit
void fixFit()
Definition: GLOFNavAlm.cpp:103
gnsstk::Xvt::health
HealthStatus health
Health status of satellite at ref time.
Definition: Xvt.hpp:157
gnsstk::GLOFNavAlm::NumberCruncher::Deltas::deltaa
double deltaa
Definition: GLOFNavAlm.hpp:225
gnsstk::DumpDetail::Terse
@ Terse
Aptly named, multiple lines of output with no labels.
gnsstk::GLOFNavAlm::dump
void dump(std::ostream &s, DumpDetail dl) const override
Definition: GLOFNavAlm.cpp:119
std::tan
double tan(gnsstk::Angle x)
Definition: Angle.hpp:148
gnsstk::CommonTime::getTimeSystem
TimeSystem getTimeSystem() const
Obtain time system info (enum).
Definition: CommonTime.cpp:288
gnsstk::DumpDetail
DumpDetail
Specify level of detail for dump output.
Definition: DumpDetail.hpp:51
gnsstk::GLOFNavAlm::dumpTerse
void dumpTerse(std::ostream &s) const
Definition: GLOFNavAlm.cpp:206
gnsstk::GLOFNavAlm::NumberCruncher::a
double a
Semi-major axis (m)
Definition: GLOFNavAlm.hpp:243
gnsstk::printTime
std::string printTime(const CommonTime &t, const std::string &fmt)
Definition: TimeString.cpp:64
gnsstk::GLOFNavAlm::J
static const GNSSTK_EXPORT double J
Some constant or other related to C20.
Definition: GLOFNavAlm.hpp:73
DebugTrace.hpp
std
Definition: Angle.hpp:142
gnsstk::GLOFNavAlm::NumberCruncher::coslambdaBar
double coslambdaBar
cos(lambdaBar)
Definition: GLOFNavAlm.hpp:245
gnsstk::GLOFNavAlm::freqnA
int freqnA
Frequency offset (H_n^A).
Definition: GLOFNavAlm.hpp:287
gnsstk::GLOFNavAlm::NumberCruncher::Jsini2Term
double Jsini2Term
JTerm * sini2.
Definition: GLOFNavAlm.hpp:260
GLOFNavEph.hpp
gnsstk::GLOFNavAlm::NumberCruncher::Deltas::setDeltas
void setDeltas(const NumberCruncher &nc, double a, double tau, double n)
Definition: GLOFNavAlm.cpp:620
gnsstk::GLOFNavAlm::mu
static const GNSSTK_EXPORT double mu
Gravitational constant.
Definition: GLOFNavAlm.hpp:59
GNSSTK_THROW
#define GNSSTK_THROW(exc)
Definition: Exception.hpp:366
DEBUGTRACE_FUNCTION
#define DEBUGTRACE_FUNCTION()
Definition: DebugTrace.hpp:117
gnsstk::GLOFNavAlm::C20Term
static const GNSSTK_EXPORT double C20Term
Term used in computing orbit.
Definition: GLOFNavAlm.hpp:75
gnsstk::GLOFNavData::satType
GLOFNavSatType satType
Satellite type (M_n: GLONASS or GLONASS-M).
Definition: GLOFNavData.hpp:68
gnsstk::GLOFNavAlm::NumberCruncher
Class to assist in doing all the math to get the XVT.
Definition: GLOFNavAlm.hpp:136
gnsstk::GLOFNavAlm::NumberCruncher::Deltas::deltaOMEGA
double deltaOMEGA
Definition: GLOFNavAlm.hpp:228
gnsstk::GLOFNavAlm::tLambdanA
double tLambdanA
Time of ascending node crossing (t_lambda_n^A).
Definition: GLOFNavAlm.hpp:284
gnsstk::Xvt::computeRelativityCorrection
virtual double computeRelativityCorrection(void)
Definition: Xvt.cpp:98
example3.mu
int mu
Definition: example3.py:36
gnsstk::GLOFNavAlm::deltainA
double deltainA
Correction to mean inclination (Delta i_n^A).
Definition: GLOFNavAlm.hpp:281
gnsstk::GLOFNavAlm::NumberCruncher::cosi
double cosi
cos(i)
Definition: GLOFNavAlm.hpp:256
gnsstk::GLOFNavAlm::NumberCruncher::cos2lambdaBar
double cos2lambdaBar
cos(2*lambdaBar)
Definition: GLOFNavAlm.hpp:247
GLOFNavAlm.hpp
gnsstk::NavSatelliteID::xmitSat
SatID xmitSat
ID of the satellite transmitting the nav data.
Definition: NavSatelliteID.hpp:170
gnsstk::GLOFNavAlm::getXvt
bool getXvt(const CommonTime &when, Xvt &xvt, const ObsID &=ObsID()) override
Definition: GLOFNavAlm.cpp:86
gnsstk::GLOFNavAlm::ae
static const GNSSTK_EXPORT double ae
Equatorial radius of Earth in km.
Definition: GLOFNavAlm.hpp:61
gnsstk::Xvt::Unhealthy
@ Unhealthy
Sat is marked unhealthy, do not use PVT.
Definition: Xvt.hpp:94
gnsstk::GLOFNavAlm::NumberCruncher::sin4lambdaBar
double sin4lambdaBar
sin(4*lambdaBar)
Definition: GLOFNavAlm.hpp:252
TimeString.hpp
gnsstk::GLOFNavAlm::NumberCruncher::JsinTerm
double JsinTerm
JTerm * (1-TH*sini2)
Definition: GLOFNavAlm.hpp:259
gnsstk::NavMessageType::Almanac
@ Almanac
Low-precision orbits for other than the transmitting SV.
gnsstk::GLOFNavAlm::NumberCruncher::Deltas::Deltas
Deltas()
Initialize everything to NaN.
Definition: GLOFNavAlm.cpp:590


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