gdc.hpp
Go to the documentation of this file.
1 //==============================================================================
2 //
3 // This file is part of GNSSTk, the ARL:UT GNSS Toolkit.
4 //
5 // The GNSSTk is free software; you can redistribute it and/or modify
6 // it under the terms of the GNU Lesser General Public License as published
7 // by the Free Software Foundation; either version 3.0 of the License, or
8 // any later version.
9 //
10 // The GNSSTk is distributed in the hope that it will be useful,
11 // but WITHOUT ANY WARRANTY; without even the implied warranty of
12 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 // GNU Lesser General Public License for more details.
14 //
15 // You should have received a copy of the GNU Lesser General Public
16 // License along with GNSSTk; if not, write to the Free Software Foundation,
17 // Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110, USA
18 //
19 // This software was developed by Applied Research Laboratories at the
20 // University of Texas at Austin.
21 // Copyright 2004-2022, The Board of Regents of The University of Texas System
22 //
23 //==============================================================================
24 
25 //==============================================================================
26 //
27 // This software was developed by Applied Research Laboratories at the
28 // University of Texas at Austin, under contract to an agency or agencies
29 // within the U.S. Department of Defense. The U.S. Government retains all
30 // rights to use, duplicate, distribute, disclose, or release this software.
31 //
32 // Pursuant to DoD Directive 523024
33 //
34 // DISTRIBUTION STATEMENT A: This software has been approved for public
35 // release, distribution is unlimited.
36 //
37 //==============================================================================
38 
47 #ifndef GNSSTK_DISCONTINUITY_CORRECTOR_INCLUDE
48 #define GNSSTK_DISCONTINUITY_CORRECTOR_INCLUDE
49 
50 #include <fstream>
51 #include <iostream>
52 #include <map>
53 #include <sstream>
54 #include <string>
55 #include <vector>
56 
57 #include "gnsstk_export.h"
58 #include "Exception.hpp"
59 #include "Epoch.hpp"
60 #include "Exception.hpp"
61 #include "FDiffFilter.hpp"
62 #include "FirstDiffFilter.hpp"
63 #include "RinexSatID.hpp"
64 #include "SatPass.hpp"
65 #include "WindowFilter.hpp"
66 
67 namespace gnsstk
68 {
69  //---------------------------------------------------------------------------
82  class Arc
83  {
84  friend class gdc;
85 
86  private:
88  static std::map<unsigned, std::string> create_mark_string_map()
89  {
90  std::map<unsigned, std::string> m;
91  m[BEG] = std::string("Begin");
92  m[WLSLIP] = std::string("WLslip");
93  m[GFSLIP] = std::string("GFslip");
94  m[WLFIX] = std::string("WLfix");
95  m[GFFIX] = std::string("GFfix");
96  m[WLMARK] = std::string("WLmark");
97  m[GFMARK] = std::string("GFmark");
98  m[REJ] = std::string("Reject");
99  return m;
100  }
101 
102  public:
103  // NB cannot use markStr[...] since its const -- use iterators
105  static const std::map<unsigned, std::string> markStr;
106 
108  static const unsigned
109  BEG;
110  static const unsigned WLSLIP;
111  static const unsigned GFSLIP;
112  static const unsigned WLFIX;
113  static const unsigned GFFIX;
114  static const unsigned GFMARK;
115  static const unsigned WLMARK;
116  static const unsigned
117  REJ;
118 
119  // -------------------------------------------------------------------
121  class Arcinfo
122  {
123  public:
125  Arcinfo() : Nslip(0), step(0.0), n(0), ave(0.0), sig(0.0) {}
126 
127  // member data
128  double
130  double sigma;
133  // TD half-cycles?
134  int Nslip;
135  int n;
139  double ave;
140  double sig;
141  }; // end class Arcinfo
143 
144  // -------------------------------------------------------------------
145  // member data
146 
147  // these are used more for "break" information
148  unsigned
150  int index;
151  unsigned npts;
152  unsigned ngood;
153 
155  Arcinfo WLinfo, GFinfo; // others? array? IF?
156 
157  std::string message;
158 
159  // -------------------------------------------------------------------
160  // member functions
161 
163  Arc() { init(); }
164 
166  Arc(int ind, unsigned n, unsigned ng, unsigned m)
167  {
168  init();
169  mark = m;
170  index = ind;
171  npts = n;
172  ngood = ng;
173  }
174 
176  void init()
177  {
178  mark = 0;
179  index = -1;
180  npts = ngood = 0;
181  WLinfo = Arcinfo();
182  GFinfo = Arcinfo();
183  message = std::string();
184  }
185 
187  Arc(const FilterHit<double>& seg)
188  {
189  init();
190  index = seg.index;
191  if (seg.type == FilterHit<double>::BOD)
192  {
193  mark = BEG; // NB BEG != FilterHit::BOD
194  }
195  else
196  {
197  mark = 0;
198  }
199  npts = seg.npts;
200  ngood = seg.ngood;
201  }
202 
204  Arc(const Arc& right)
205  {
206  init();
207  *this = right;
208  }
209 
211  Arc& operator=(const Arc& right)
212  {
213  index = right.index;
214  npts = right.npts;
215  ngood = right.ngood;
216  mark = right.mark;
217  message = right.message;
218  WLinfo = right.WLinfo;
219  GFinfo = right.GFinfo;
220  return *this;
221  }
222 
224  static std::string markString(const unsigned mark)
225  {
226  std::map<unsigned, std::string>::const_iterator it;
227  it = markStr.find(mark);
228  if (it != markStr.end())
229  {
230  return it->second;
231  }
232  else
233  {
234  return std::string("Unknown");
235  }
236  }
237 
240  std::string markString() const
241  {
242  std::string msg;
243  std::map<unsigned, std::string>::const_iterator it;
244  // NB don't use markStr[it->first]; b/c its const
245  for (it = markStr.begin(); it != markStr.end(); ++it)
246  if (mark & it->first)
247  {
248  msg += std::string(msg.empty() ? "" : "/") + it->second;
249  }
250  return msg;
251  }
252 
254  std::string brkString() const
255  {
256  std::ostringstream os;
257  os << markString() << " good/tot=" << ngood << "/" << npts << "="
258  << std::fixed << std::setprecision(2) << 100. * ngood / double(npts)
259  << "%";
260  return os.str();
261  }
262 
268  std::string asString(const int prec = 3) const
269  {
270  std::ostringstream os;
271  os << std::fixed << std::setprecision(prec);
272  os << brkString();
273 
274  if (markString() != "BEG" && markString() != "REJ")
275  {
276  os << " NWL=" << WLinfo.Nslip << " dWL=" << WLinfo.step << "wl";
277  }
278  else
279  {
280  os << " WL";
281  }
282  if (WLinfo.n > 0)
283  {
284  os << " " << WLinfo.n << " " << WLinfo.ave << " +- " << WLinfo.sig;
285  }
286  else
287  {
288  os << " NoAn";
289  }
290 
291  if (markString() != "BEG" && markString() != "REJ")
292  {
293  os << " NGF=" << GFinfo.Nslip << " dGF=" << GFinfo.step << "wl";
294  }
295  else
296  {
297  os << " GF";
298  }
299  if (GFinfo.n > 0)
300  {
301  os << " " << GFinfo.n << " " << GFinfo.ave << " +- " << GFinfo.sig;
302  }
303  else
304  {
305  os << " NoAn";
306  }
307 
308  return os.str();
309  }
310 
311  }; // end class Arc
312 
313  //---------------------------------------------------------------------------------
314  //---------------------------------------------------------------------------------
319  class gdc
320  {
321  public:
323  gdc() { init(); }
324 
326  ~gdc() {}
327 
336  bool setParameter(std::string cmd);
337 
347  bool setParameter(std::string label, double value);
348 
354  double getParameter(std::string label) { return CFG[label]; }
355 
364  void DisplayParameterUsage(std::ostream& os,
365  std::string tag = std::string(),
366  bool advanced = false);
367 
373  double cfg_func(std::string a)
374  {
375  if (CFGdesc[a] == std::string())
376  {
377  Exception e("cfg(UNKNOWN LABEL) : " + a);
378  GNSSTK_THROW(e);
379  }
380  return CFG[a];
381  }
382 
384  int getUniqueNumber() { return unique; }
385 
391  void ForceUniqueNumber(int n) { unique = n; }
392 
393  //---------------------------------------------------------------------------
464  int DiscontinuityCorrector(SatPass& SP, std::string& retMsg,
465  std::vector<std::string>& cmds,
466  int GLOn = -99);
467 
468  //---------------------------------------------------------------------------
480  const RinexSatID& sat, const double& nominalDT, const Epoch& beginTime,
481  std::vector<double> dataL1, std::vector<double> dataL2,
482  std::vector<double> dataP1, std::vector<double> dataP2,
483  std::vector<double> dt, std::vector<int> flags, std::string& retMsg,
484  std::vector<std::string>& cmds, int GLOn = -99,
485  std::string outfmt = std::string("%4F %10.3g"));
486 
487  private:
489  static std::vector<unsigned> create_vector_SLIP()
490  {
491  std::vector<unsigned> v;
492  v.push_back(Arc::WLSLIP);
493  v.push_back(Arc::GFSLIP);
494  return v;
495  }
497  static std::vector<unsigned> create_vector_FIX()
498  {
499  std::vector<unsigned> v;
500  v.push_back(Arc::WLFIX);
501  v.push_back(Arc::GFFIX);
502  return v;
503  }
505  static std::vector<std::string> create_vector_LAB()
506  {
507  std::vector<std::string> v;
508  v.push_back("WL");
509  v.push_back("GF");
510  return v;
511  }
512 
513  protected:
515  GNSSTK_EXPORT
516  static const std::string GDCVersion;
517 
518  // NB flags[] is either good (0) or not (!0);
519  // flags have NOTHING to do with either SatPass or Arc::marks
520  // Arcs handles BEG, SLIP/FIX, and GAP(new BEG); flags handle bad data
521  // w/in Arc NB BAD != SatPass::BAD but ONLY SatPass::BAD on input => BAD
523  static const unsigned OK;
524  static const unsigned BAD;
525  static const unsigned
527  static const unsigned
529  static const unsigned WLSHORT;
530  static const unsigned GFSHORT;
531  static const unsigned
533  // others?
534 
536  static const unsigned WL;
537  static const unsigned GF;
538  static const std::vector<unsigned> SLIP, FIX;
539  static const std::vector<std::string> LAB;
540  static std::vector<double> wl;
541 
542  //---------------------------------------------------------------------------
543  // configuration
545  std::map<std::string, double> CFG;
546 
548  std::map<std::string, std::string> CFGdesc;
549 
551  int CFGindex;
552  std::map<int, std::string> CFGlist;
553 
554  //---------------------------------------------------------------------------
556  int unique;
557  std::string
558  tag;
559  std::string SPSstr;
560 
563  bool isGLO;
564  double dt;
566 
567  std::string outfmt;
568  int oswidth;
569  int osprec;
570 
571  int GLOchan;
572  // just to keep numerical range down
573  double WLbias;
574  double GFbias;
575  // approximate; for output of editing commands only
576  long long
578  long long
580 
581  double wl1;
582  double wl2;
583  double alpha;
584  double beta;
585  double wlWL;
586  double wlGF;
587  double wlNL;
588 
593  std::vector<double> dataWL, dataGF;
594 
599  std::vector<double> xdata;
600 
601  // NB flags must be int, not unsigned, for StatsFilter processing
606  std::vector<int> flags;
607 
622  std::map<int, Arc> Arcs;
623 
624  // member functions
625  //---------------------------------------------------------------------------
626 
628  void init();
629 
637  int ProcessOneCombo(const unsigned which);
638 
646  int GrossProcessing(const unsigned which);
647 
655  int FineProcessing(const unsigned which);
656 
666  int filterFirstDiff(const unsigned which, const std::string label,
667  double limit, std::vector<FilterHit<double>>& hits);
668 
678  int filterWindow(const unsigned which, const std::string label,
679  double limit, std::vector<FilterHit<double>>& hits);
680 
691  int mergeFilterResultsIntoArcs(std::vector<FilterHit<double>>& hits,
692  const unsigned which);
693 
694  // the next three are called by mergeFilterResultsIntoArcs()
695 
705  void flagBadData(const FilterHit<double>& hit, const unsigned flagvalue);
706 
714  bool addArc(const int index, const unsigned mark);
715 
717  void fixUpArcs();
718 
724  void recomputeArcs();
725 
727  inline unsigned computeNgood(Arc& arc)
728  {
729  arc.ngood = 0;
730  for (unsigned int i = arc.index; i < arc.index + arc.npts; ++i)
731  {
732  if (flags[i] == OK)
733  {
734  arc.ngood++;
735  }
736  }
737  return arc.ngood;
738  }
739 
745  void getArcStats(const unsigned which)
746  {
747  try
748  {
749  for (std::map<int, Arc>::iterator ait = Arcs.begin();
750  ait != Arcs.end(); ++ait)
751  getArcStats(ait, which);
752  }
753  catch (Exception& e)
754  {
755  GNSSTK_RETHROW(e);
756  }
757  }
758 
767  void getArcStats(std::map<int, Arc>::iterator& ait, const unsigned which);
768 
774  void findLargeGaps();
775 
788  int fixSlips(const unsigned which);
789 
798  std::map<int, int> findGaps(const Arc& arc);
799 
801  void dumpData(std::ostream& os, const std::string msg = std::string());
802 
804  Epoch xtime(const int& i)
805  {
806  if (i >= dataWL.size())
807  {
808  GNSSTK_THROW(Exception("Index out of range in xtime"));
809  }
810  Epoch tt(beginT);
811  tt += xdata[i];
812  return tt;
813  }
814 
820  void findArc(const unsigned int ind, std::map<int, Arc>::iterator& ait)
821  {
822  if (int(ind) < ait->second.index)
823  {
824  GNSSTK_THROW(Exception("index before given Arc"));
825  }
826 
827  while (ait != Arcs.end() &&
828  ind >= ait->second.index + ait->second.npts)
829  ++ait;
830 
831  if (ait == Arcs.end()) // index not found
832  {
833  GNSSTK_THROW(Exception("index after end of Arcs"));
834  }
835  }
836 
845  void DumpArcs(const std::string& tag, const std::string& label,
846  int prec = -1);
847 
854  void DumpHits(const std::vector<FilterHit<double>>& filterResults,
855  const std::string& tag, const std::string& label,
856  int prec = -1);
857 
859  std::string returnMessage(int prec = -1, int wid = -1);
860 
869  void applyFixesToSatPass(SatPass& SP);
870 
878  void generateCmds(std::vector<std::string>& cmds);
879 
885  int FinalCheck();
886 
887  }; // end class gdc
888 
889 } // end namespace gnsstk
890 
891 //------------------------------------------------------------------------------------
892 #endif // GNSSTK_DISCONTINUITY_CORRECTOR_INCLUDE
gnsstk::gdc::FinalCheck
int FinalCheck()
Definition: gdc.cpp:1273
gnsstk::FilterHit::index
unsigned int index
index in the data array(s) at which this event occurs
Definition: StatsFilterHit.hpp:91
gnsstk::gdc::wlWL
double wlWL
WL wavelength ~86cm, in meters.
Definition: gdc.hpp:585
gnsstk::Arc::Arcinfo::n
int n
number of points in stats(ave,sig) - may be > npts in Arc
Definition: gdc.hpp:138
SatPass.hpp
gnsstk::gdc::OK
static const unsigned OK
Values for flags[] = bit maps.
Definition: gdc.hpp:523
gnsstk::gdc::CFGdesc
std::map< std::string, std::string > CFGdesc
map containing configuration labels and their descriptions
Definition: gdc.hpp:548
gnsstk::gdc::~gdc
~gdc()
destructor
Definition: gdc.hpp:326
gnsstk::gdc::findLargeGaps
void findLargeGaps()
Definition: gdc.cpp:1075
gnsstk::gdc::create_vector_LAB
static std::vector< std::string > create_vector_LAB()
helper routine to initialize vectors
Definition: gdc.hpp:505
gnsstk::gdc::SLIP
static const std::vector< unsigned > SLIP
Definition: gdc.hpp:538
gnsstk::gdc::GLOchan
int GLOchan
GLONASS frequency channel (-99 by default in GDC())
Definition: gdc.hpp:571
gnsstk::gdc::ForceUniqueNumber
void ForceUniqueNumber(int n)
Definition: gdc.hpp:391
gnsstk::gdc::dataWL
std::vector< double > dataWL
Definition: gdc.hpp:593
gnsstk::gdc::create_vector_SLIP
static std::vector< unsigned > create_vector_SLIP()
helper routine to initialize vectors
Definition: gdc.hpp:489
gnsstk::gdc::wlNL
double wlNL
NL wavelength ~10.7cm, in meters.
Definition: gdc.hpp:587
gnsstk::gdc::DiscontinuityCorrector
int DiscontinuityCorrector(SatPass &SP, std::string &retMsg, std::vector< std::string > &cmds, int GLOn=-99)
Definition: gdc.cpp:144
gnsstk::gdc::flags
std::vector< int > flags
Definition: gdc.hpp:606
gnsstk::Arc::Arcinfo::sigma
double sigma
for slips, RSS future and past sigma on the data
Definition: gdc.hpp:132
gnsstk::gdc::dt
double dt
data time spacing, from SatPass, in sec
Definition: gdc.hpp:564
gnsstk::gdc::WLSHORT
static const unsigned WLSHORT
flag for data with Arc.ngood < MinPts
Definition: gdc.hpp:529
gnsstk::gdc::tag
std::string tag
begin each output line with 'GDC <unique>' ( <label>)
Definition: gdc.hpp:558
gnsstk::gdc::wlGF
double wlGF
GF wavelength = wl2-wl1 = 5.376cm, in meters.
Definition: gdc.hpp:586
gnsstk::Arc::index
int index
index in data arrays of beginning ("break")
Definition: gdc.hpp:150
gnsstk::Arc::brkString
std::string brkString() const
string giving brief summary of break info e.g. WLslip/GFslip/WLfix 445 pts 438 good
Definition: gdc.hpp:254
gnsstk::gdc::ProcessOneCombo
int ProcessOneCombo(const unsigned which)
Definition: gdc.cpp:444
gnsstk::gdc::CFG
std::map< std::string, double > CFG
map containing configuration labels and their values
Definition: gdc.hpp:545
gnsstk::gdc::DumpHits
void DumpHits(const std::vector< FilterHit< double >> &filterResults, const std::string &tag, const std::string &label, int prec=-1)
Definition: gdc.cpp:1411
gnsstk::gdc::ISOLATED
static const unsigned ISOLATED
flag for isolated good data (< MinPts)
Definition: gdc.hpp:532
gnsstk::Arc::GFinfo
Arcinfo GFinfo
Definition: gdc.hpp:155
gnsstk::gdc::GFbias
double GFbias
bias determined by initial value of GF, in wl
Definition: gdc.hpp:574
gnsstk::gdc::beginT
Epoch beginT
begin time from SatPass
Definition: gdc.hpp:565
gnsstk::gdc::getParameter
double getParameter(std::string label)
Definition: gdc.hpp:354
gnsstk::gdc::fixSlips
int fixSlips(const unsigned which)
Definition: gdc.cpp:1193
gnsstk::Arc::WLMARK
static const unsigned WLMARK
64 slip suspected but not found on WL
Definition: gdc.hpp:115
gnsstk::Arc::GFSLIP
static const unsigned GFSLIP
4 slip found on GF
Definition: gdc.hpp:111
gnsstk::SatPass
Definition: SatPass.hpp:71
gnsstk::gdc::WL
static const unsigned WL
conveniences
Definition: gdc.hpp:536
gnsstk::Arc::Arcinfo::Nslip
int Nslip
Definition: gdc.hpp:134
gnsstk::Arc::npts
unsigned npts
number of points in the segment -> last index
Definition: gdc.hpp:151
gnsstk::gdc::CFGlist
std::map< int, std::string > CFGlist
Definition: gdc.hpp:552
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::gdc::dumpData
void dumpData(std::ostream &os, const std::string msg=std::string())
dump the data stored in the data arrays
Definition: gdc.cpp:1387
gnsstk::gdc::CFGindex
int CFGindex
map used to keep them in order
Definition: gdc.hpp:551
gnsstk::Arc::Arcinfo
little class used to store information about one data array within this Arc
Definition: gdc.hpp:121
gnsstk::Arc::init
void init()
initialize (clear or empty) an Arc
Definition: gdc.hpp:176
gnsstk::gdc::mergeFilterResultsIntoArcs
int mergeFilterResultsIntoArcs(std::vector< FilterHit< double >> &hits, const unsigned which)
Definition: gdc.cpp:755
gnsstk::Arc::GFFIX
static const unsigned GFFIX
16 slip fixed on GF
Definition: gdc.hpp:113
gnsstk::Arc::ngood
unsigned ngood
number of good data points in the segment
Definition: gdc.hpp:152
gnsstk::Arc::Arcinfo::Arcinfo
Arcinfo()
constructor
Definition: gdc.hpp:125
gnsstk::gdc::N2bias
long long N2bias
bias in L2 at initial point (from P2=wl2*(N2bias+L2))
Definition: gdc.hpp:579
gnsstk::gdc::recomputeArcs
void recomputeArcs()
Definition: gdc.cpp:971
gnsstk::gdc::sat
RinexSatID sat
member data used internally
Definition: gdc.hpp:562
gnsstk::gdc::wl
static std::vector< double > wl
vector of wavelengths
Definition: gdc.hpp:540
gnsstk::Exception
Definition: Exception.hpp:151
gnsstk::gdc::SPSstr
std::string SPSstr
SPS output of SatPass, or generated equivalent.
Definition: gdc.hpp:559
gnsstk::Arc::create_mark_string_map
static std::map< unsigned, std::string > create_mark_string_map()
helper routine to initialize markStr map
Definition: gdc.hpp:88
gnsstk::gdc::gdc
gdc()
constructor; this sets a full default set of parameters.
Definition: gdc.hpp:323
gnsstk::Arc::Arcinfo::step
double step
Definition: gdc.hpp:129
gnsstk::gdc::N1bias
long long N1bias
bias in L1 at initial point (from P1=wl1*(N1bias+L1))
Definition: gdc.hpp:577
gnsstk::gdc::findGaps
std::map< int, int > findGaps(const Arc &arc)
Definition: gdc.cpp:1146
gnsstk::gdc::wl1
double wl1
L1 wavelength, from sat, in meters.
Definition: gdc.hpp:581
gnsstk::Arc::GFMARK
static const unsigned GFMARK
32 slip suspected but not found on GF
Definition: gdc.hpp:114
gnsstk::gdc::GFOUTLIER
static const unsigned GFOUTLIER
flag for data called outlier by GF filter
Definition: gdc.hpp:528
gnsstk::gdc::findArc
void findArc(const unsigned int ind, std::map< int, Arc >::iterator &ait)
Definition: gdc.hpp:820
gnsstk::gdc::returnMessage
std::string returnMessage(int prec=-1, int wid=-1)
build the string that is returned by the discontinuity corrector
Definition: gdc.cpp:1444
gnsstk::gdc::BAD
static const unsigned BAD
flag for bad data = 1 NB SatPass::BAD = 0
Definition: gdc.hpp:524
gnsstk::gdc::dataGF
std::vector< double > dataGF
Definition: gdc.hpp:593
gnsstk::Arc::WLSLIP
static const unsigned WLSLIP
2 slip found on WL
Definition: gdc.hpp:110
gnsstk::gdc::WLbias
double WLbias
bias determined by initial value of WL, in wl
Definition: gdc.hpp:573
gnsstk::Arc::mark
unsigned mark
bitmap identifying actions that created or modified Arc
Definition: gdc.hpp:149
FDiffFilter.hpp
gnsstk::gdc::filterFirstDiff
int filterFirstDiff(const unsigned which, const std::string label, double limit, std::vector< FilterHit< double >> &hits)
Definition: gdc.cpp:621
gnsstk::gdc::fixUpArcs
void fixUpArcs()
modify Arcs: recompute npts and ngood, remove empty Arcs
Definition: gdc.cpp:946
gnsstk::gdc::isGLO
bool isGLO
true if this is a GLONASS satellite
Definition: gdc.hpp:563
gnsstk::gdc::oswidth
int oswidth
output stream width
Definition: gdc.hpp:568
gnsstk::Arc::Arcinfo::sig
double sig
Definition: gdc.hpp:140
gnsstk::gdc::GF
static const unsigned GF
used internally to denote the GF combo
Definition: gdc.hpp:537
gnsstk::gdc::Arcs
std::map< int, Arc > Arcs
Definition: gdc.hpp:622
gnsstk::FilterHit::npts
unsigned int npts
number data points in segment (= a delta index)
Definition: StatsFilterHit.hpp:93
gnsstk::gdc::xtime
Epoch xtime(const int &i)
compute a time tag from array index: beginT + (xdata[i]==ndt)*dt
Definition: gdc.hpp:804
gnsstk::Arc::Arc
Arc(const Arc &right)
copy constructor
Definition: gdc.hpp:204
gnsstk::gdc::flagBadData
void flagBadData(const FilterHit< double > &hit, const unsigned flagvalue)
Definition: gdc.cpp:893
gnsstk::Arc::operator=
Arc & operator=(const Arc &right)
operator=
Definition: gdc.hpp:211
gnsstk::Arc
Definition: gdc.hpp:82
FirstDiffFilter.hpp
gnsstk::gdc::WLOUTLIER
static const unsigned WLOUTLIER
flag for data called outlier by WL filter
Definition: gdc.hpp:526
gnsstk::Arc::markString
std::string markString() const
Definition: gdc.hpp:240
gnsstk::gdc::applyFixesToSatPass
void applyFixesToSatPass(SatPass &SP)
Definition: gdc.cpp:1600
gnsstk::gdc::DisplayParameterUsage
void DisplayParameterUsage(std::ostream &os, std::string tag=std::string(), bool advanced=false)
Definition: gdc.cpp:2007
GNSSTK_RETHROW
#define GNSSTK_RETHROW(exc)
Definition: Exception.hpp:369
gnsstk::Arc::Arc
Arc()
empty c'tor
Definition: gdc.hpp:163
gnsstk::gdc::LAB
static const std::vector< std::string > LAB
vector of labels: WL, GF
Definition: gdc.hpp:539
gnsstk::gdc::getUniqueNumber
int getUniqueNumber()
get the unique number; note that it is incremented at start of Disc..Corr()
Definition: gdc.hpp:384
gnsstk::gdc::unique
int unique
unique number, counting passes or calls
Definition: gdc.hpp:556
gnsstk::Arc::Arc
Arc(int ind, unsigned n, unsigned ng, unsigned m)
c'tor with minimum info
Definition: gdc.hpp:166
WindowFilter.hpp
gnsstk::gdc::computeNgood
unsigned computeNgood(Arc &arc)
recompute the number of good points in an Arc
Definition: gdc.hpp:727
gnsstk::Arc::markStr
static const std::map< unsigned, std::string > markStr
strings describing values used for Arc::mark
Definition: gdc.hpp:105
gnsstk::FilterHit::ngood
unsigned int ngood
number of good (flag==0) points in this segment
Definition: StatsFilterHit.hpp:94
gnsstk::Arc::WLFIX
static const unsigned WLFIX
8 slip fixed on WL
Definition: gdc.hpp:112
gnsstk::gdc::alpha
double alpha
alpha, from sat
Definition: gdc.hpp:583
gnsstk::gdc::generateCmds
void generateCmds(std::vector< std::string > &cmds)
Definition: gdc.cpp:1706
gnsstk::RinexSatID
Definition: RinexSatID.hpp:63
Exception.hpp
Epoch.hpp
gnsstk::gdc
Definition: gdc.hpp:319
gnsstk::gdc::DumpArcs
void DumpArcs(const std::string &tag, const std::string &label, int prec=-1)
Definition: gdc.cpp:1427
gnsstk::gdc::GrossProcessing
int GrossProcessing(const unsigned which)
Definition: gdc.cpp:483
gnsstk::gdc::GDCVersion
static const GNSSTK_EXPORT std::string GDCVersion
Version string.
Definition: gdc.hpp:516
gnsstk::Epoch
Definition: Epoch.hpp:123
gnsstk::gdc::getArcStats
void getArcStats(const unsigned which)
Definition: gdc.hpp:745
gnsstk::gdc::cfg_func
double cfg_func(std::string a)
Definition: gdc.hpp:373
GNSSTK_THROW
#define GNSSTK_THROW(exc)
Definition: Exception.hpp:366
gnsstk::FilterHit::type
event type
type of event: BOD, outlier(s), slip, other
Definition: StatsFilterHit.hpp:88
gnsstk::gdc::create_vector_FIX
static std::vector< unsigned > create_vector_FIX()
helper routine to initialize vectors
Definition: gdc.hpp:497
gnsstk::gdc::beta
double beta
beta, from sat
Definition: gdc.hpp:584
gnsstk::Arc::REJ
static const unsigned REJ
128 segment of bad data - returnMessage() only
Definition: gdc.hpp:117
gnsstk::Arc::message
std::string message
readable description of whatever
Definition: gdc.hpp:157
gnsstk::Arc::WLinfo
Arcinfo WLinfo
Arcinfo for each datatype.
Definition: gdc.hpp:155
RinexSatID.hpp
gnsstk::gdc::setParameter
bool setParameter(std::string cmd)
Definition: gdc.cpp:1894
gnsstk::FilterHit
Definition: StatsFilterHit.hpp:68
GLOn
int GLOn
Definition: DiscCorr.cpp:655
gnsstk::gdc::wl2
double wl2
L2 wavelength, from sat, in meters.
Definition: gdc.hpp:582
gnsstk::Arc::BEG
static const unsigned BEG
mark bitmap values for characterizing Arc: BEG, slips, fixes, etc; see init()
Definition: gdc.hpp:109
gnsstk::gdc::osprec
int osprec
output stream precision
Definition: gdc.hpp:569
gnsstk::gdc::GFSHORT
static const unsigned GFSHORT
flag for data with Arc.ngood < MinPts
Definition: gdc.hpp:530
gnsstk::gdc::xdata
std::vector< double > xdata
Definition: gdc.hpp:599
gnsstk::Arc::asString
std::string asString(const int prec=3) const
Definition: gdc.hpp:268
gnsstk::Arc::Arcinfo::ave
double ave
average value of the data in the Arc (data units)
Definition: gdc.hpp:139
gnsstk::gdc::outfmt
std::string outfmt
output time format, from SatPass
Definition: gdc.hpp:567
gnsstk::gdc::addArc
bool addArc(const int index, const unsigned mark)
Definition: gdc.cpp:913
gnsstk::gdc::FIX
static const std::vector< unsigned > FIX
slips, fixes
Definition: gdc.hpp:538
gnsstk::gdc::init
void init()
Initializer used in c'tor to define default configuration.
Definition: gdc.cpp:2076
gnsstk::gdc::FineProcessing
int FineProcessing(const unsigned which)
Definition: gdc.cpp:552
gnsstk::gdc::filterWindow
int filterWindow(const unsigned which, const std::string label, double limit, std::vector< FilterHit< double >> &hits)
Definition: gdc.cpp:673
gnsstk::Arc::markString
static std::string markString(const unsigned mark)
convert one mark into a readable string
Definition: gdc.hpp:224
gnsstk::Arc::Arc
Arc(const FilterHit< double > &seg)
create an Arc from a FilterHit (filters returns a vector of FilterHit)
Definition: gdc.hpp:187


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