FDiffFilter.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 
96 #ifndef FDIFF_FILTER_INCLUDE
97 #define FDIFF_FILTER_INCLUDE
98 
99 #include "RobustStats.hpp"
100 #include "Stats.hpp"
101 #include "StatsFilterHit.hpp"
102 #include "StringUtils.hpp"
103 
104 #include <vector>
105 
106 namespace gnsstk
107 {
108  //---------------------------------------------------------------------------------
109  // TODO
110 
111  //---------------------------------------------------------------------------------
113  template <class T> class IterativeFDiffFilter;
114 
115  //---------------------------------------------------------------------------------
131  template <class T> class FDiffFilter
132  {
133  private:
134  friend class IterativeFDiffFilter<T>;
135 
136  // embedded class -----------------------------------------
141  class Analysis
142  {
143  public:
146  {
147  index = 0;
148  sloInd = 0;
149  diff = sigN = T(0);
150  }
151  // member data
152  unsigned int
154  T diff;
155  T sigN;
156  T sloN;
157  int sloInd;
158  }; // end class Analysis
159 
165  std::vector<Analysis> Avec;
166 
168  std::vector<FilterHit<T>> results;
169 
170  // member data ---------------------------------------
171  int osw, osp;
172  bool noxdata;
173  bool noflags;
174 
175  const std::vector<T>
176  &xdata;
177  const std::vector<T> &data;
178  const std::vector<int>
179  &flags;
180  int ilimit;
181 
182  T fdlim;
183  T siglim;
185  unsigned int Nwind;
186  unsigned int Nsig;
187  bool doSmall;
189  std::vector<unsigned int>
191 
193 
194  public:
195  // member functions ---------------------------------------
205  FDiffFilter(const std::vector<T>& x, const std::vector<T>& d,
206  const std::vector<int>& f)
207  : data(d), xdata(x), flags(f)
208  {
209  fdlim = T(0.8);
210  siglim = T(0.3);
211  Esiglim = T(0);
212  noxdata = (xdata.size() == 0);
213  noflags = (flags.size() == 0);
214  osw = 8;
215  osp = 3;
216  Nsig = 0;
217  doSmall = true;
218  keepSigIndex = false;
219  }
220 
222  inline void setWidth(unsigned int w) { Nwind = w; }
223 
225  inline unsigned int getWidth() { return Nwind; }
226 
228  inline void setLimit(T val) { fdlim = val; }
229 
231  inline T getLimit() { return fdlim; }
232 
234  inline void setSigma(T val) { siglim = val; }
235 
237  inline T getSigma() { return siglim; }
238 
240  inline bool doSmallSlips(bool doit)
241  {
242  doSmall = doit;
243  return doit;
244  }
245 
247  inline bool doSmallSlips() { return doSmall; }
248 
250  inline bool indexHighSigmas(bool doit)
251  {
252  keepSigIndex = doit;
253  return doit;
254  }
255 
257  inline bool indexingHighSigmas() { return keepSigIndex; }
258 
260  inline void setw(int w) { osw = w; }
261 
263  inline void setprecision(int p) { osp = p; }
264 
266  inline std::vector<FilterHit<T>> getResults() { return results; }
267 
270  inline unsigned int getNhighSigma() { return Nsig; }
271 
273  inline std::vector<unsigned int> getHighSigmaIndex()
274  {
275  return sigIndexes;
276  }
277 
289  int filter(const size_t index = 0, int npts = -1);
290 
299  void computeRobustSigmaLimit(int& N, T& new_siglim);
300 
306  int analysis();
307 
312  void dump(std::ostream& s, std::string tag = std::string());
313 
314  }; // end class FDiffFilter
315 
316  //---------------------------------------------------------------------------------
317  template <class T> int FDiffFilter<T>::filter(const size_t i0, int dsize)
318  {
319  if (dsize == -1)
320  {
321  dsize = data.size() - i0;
322  }
323 
324  // largest allowed index is ilimit-1
325  ilimit = dsize + i0;
326 
327  // is there enough data? if not return -1
328  int i(i0), n(0);
329  if (!noflags)
330  {
331  while (i < ilimit && n < 2)
332  {
333  if (flags[i] == 0)
334  {
335  n++;
336  }
337  i++;
338  }
339  if (i == ilimit)
340  {
341  return -1;
342  }
343  }
344  else if (dsize < 2)
345  {
346  return -1;
347  }
348 
349  // if xdata or flags is there, make sure its big enough
350  if (!noflags && flags.size() - i0 < dsize)
351  {
352  return -3;
353  }
354 
355  // generate the analysis vector
356  Avec.clear();
357 
358  // compute stats on sigmas and data in a sliding window of width Nwind
359  gnsstk::TwoSampleStats<T> fstats; // stats on the first diffs in window
360  gnsstk::TwoSampleStats<T> dstats; // stats on the data in window
361  std::vector<T> slopes; // store slopes, for robust stats
362 
363  // loop over all data, computing first difference and stats in sliding
364  // window
365  Nsig = 0;
366  int iprev(-1), j, islope(0);
367  // start at the first good point
368  n = 0;
369  i = i0;
370  if (!noflags)
371  {
372  while (i < ilimit && flags[i])
373  i++;
374  }
375  while (i < ilimit)
376  {
377  Analysis A;
378  A.index = i;
379  n++; // count data points, just for approx slope when n==2
380 
381  // add to stats on data (for slope)
382  dstats.Add(xdata[i], data[i]);
383 
384  // compute first difference, accounting for slope of data
385  if (iprev == -1)
386  {
387  A.diff = T(0);
388  }
389  else
390  {
391  // get approx slope at first pt (often slope==0 here => OUT;
392  // index=0)
393  if (n == 2)
394  {
395  Avec[islope].sloN = // first slope = 2nd slope = d(data)/dx
396  (data[i] - data[iprev]) / (xdata[i] - xdata[iprev]);
397  }
398  // index of latest good slope
399  A.sloInd = islope;
400  // compute the difference = change in data - correction for slope
401  A.diff = data[i] - data[iprev] -
402  Avec[islope].sloN * (xdata[i] - xdata[iprev]);
403  // add diff to stats
404  fstats.Add(xdata[i], A.diff);
405  }
406 
407  // remove old data from stats buffers if full
408  j = Avec.size() - Nwind; // index of earliest of the Nwind points
409  if (fstats.N() > Nwind)
410  {
411  fstats.Subtract(xdata[Avec[j].index], Avec[j].diff);
412  }
413  if (dstats.N() > Nwind)
414  {
415  dstats.Subtract(xdata[Avec[j].index], data[Avec[j].index]);
416  }
417 
418  // NO A.sigN = fstats.SigmaYX(); // sigma first diff, given slope
419  // in fdiffs
420  A.sigN = fstats.StdDevY(); // sigma first diff
421  A.sloN = dstats.Slope(); // slope of data
422  if (A.sigN > siglim)
423  {
424  Nsig++; // count it if sigma is high
425  if (keepSigIndex)
426  {
427  sigIndexes.push_back(i);
428  }
429  }
430  else
431  {
432  islope = Avec.size(); // keep this, the most recent good slope
433  // keep slopes for roubst stats
434  slopes.push_back(A.sloN);
435  }
436 
437  Avec.push_back(A);
438  iprev = i;
439  i++;
440  if (!noflags)
441  {
442  while (i < ilimit && flags[i])
443  i++;
444  }
445  }
446 
447  // compute robust stats on slopes
449  &slopes[0], slopes.size(), medSlope, false);
450 
451  return Avec.size();
452 
453  } // end FDiffFilter::filter()
454 
455  //---------------------------------------------------------------------------------
456  template <class T>
457  void FDiffFilter<T>::computeRobustSigmaLimit(int& N, T& new_siglim)
458  {
459  new_siglim = siglim;
460  if (Avec.size() < 2)
461  {
462  N = -1;
463  return;
464  }
465 
466  // compute high-outlier limit of sigmas using robust stats
467  // compute quartiles - must sort first
468  unsigned int i;
469  std::vector<T> sd; // put sigmas in temp vector
470  for (i = 0; i < Avec.size(); i++)
471  sd.push_back(Avec[i].sigN);
472 
473  T Q1, Q3;
474  gnsstk::QSort(&sd[0], sd.size()); // sort
475  gnsstk::Robust::Quartiles(&sd[0], sd.size(), Q1, Q3); // get Quartiles
476 
477  // compute new sigma limit ; outlier limit (high) 2.5Q3-1.5Q1
478  new_siglim = 2.5 * Q3 - 1.5 * Q1;
479  if (new_siglim <= siglim)
480  {
481  N = Nsig;
482  return;
483  }
484 
485  // count up hi-sigma points
486  for (N = 0, i = 0; i < Avec.size(); i++)
487  if (Avec[i].sigN > new_siglim)
488  {
489  N++;
490  }
491  }
492 
493  //---------------------------------------------------------------------------------
494  template <class T> int FDiffFilter<T>::analysis()
495  {
496  // bool debug(true);
497 
498  // don't clear results - may be a case where caller wants to keep old ones
499 
500  // loop over analysis vector
501  // outliers have >= Nwind big sigmas
502  // unless its the first point, then there are Nwind-2 bad sigmas
503  // slips have exactly Nwind big sigmas
504  bool isBad(false);
505  int nbad(0), nout, n1st, Nw(Nwind), k; // DO NOT use unsigned
506  unsigned int i, j, bad0;
507  for (i = 0; i < Avec.size(); i++)
508  {
509  // if(debug)
510  // std::cout << "Loop " << i << " " << xdata[Avec[i].index] <<
511  // std::endl;
512 
513  if (Avec[i].sigN > siglim)
514  {
515  if (!isBad)
516  {
517  bad0 = i;
518  isBad = true;
519  }
520  nbad++;
521  }
522 
523  else if (isBad)
524  {
525  nout = int(bad0) + nbad - Nw;
526  n1st = int(i) - Nw;
527  // if(debug) std::cout << "FDFa: isBad at i " << i
528  // << " index " << Avec[i].index << " x " <<
529  // xdata[Avec[i].index]
530  // << " bad0 " << bad0 << " nbad " << nbad << " nout " << nout
531  // << " Nwind " << Nw << " 2Nw-2 " << 2*Nw-2 << std::endl;
532 
533  if (nout > 0 && nbad > Nw)
534  { // outliers - more than a slip
535  // if(debug) for(j=bad0; j<nout; j++)
536  // std::cout << "FDFa: OUT " << Avec[j].index
537  // << " " << xdata[Avec[j].index] << std::endl;
538  j = bad0;
539  FilterHit<T> fdfr;
541  fdfr.index = Avec[j].index;
542  fdfr.npts = nbad - Nw;
543  fdfr.dx =
544  xdata[Avec[int(j) + nbad - Nw].index] - xdata[Avec[j].index];
545  results.push_back(fdfr);
546  }
547 
548  else if (nbad == Nw)
549  { // slip
550  j = bad0;
551  // if(debug) std::cout << "FDFa: SLIP " << Avec[j].index <<
552  // std::fixed
553  // << " " << xdata[Avec[j].index] << std::setprecision(osp)
554  // << " " << Avec[j].diff << std::endl;
555  FilterHit<double> fdfr;
556  fdfr.type = FilterHit<T>::slip;
557  fdfr.index = Avec[j].index;
558  fdfr.sigma = Avec[j].sigN;
559 
560  // find number of missing pts before the slip
561  k = Avec[j].index - 1; // j is an Avec[] index
562  if (noflags && k > 0)
563  {
564  k--; // NB k is int
565  }
566  else
567  {
568  while (k > 0 && flags[k] != 0)
569  k--; // k is the data[] index
570  }
571  fdfr.dx = xdata[Avec[j].index] - xdata[k];
572  fdfr.npts = Avec[j].index - k;
573 
574  // get the step = first difference of data across slip
575  fdfr.step = Avec[j].diff;
576  // score here is just step/fdlim as a percentage (max 100)
577  fdfr.score =
578  (unsigned int)(0.5 + 100. * ::fabs(fdfr.step) / fdlim);
579  if (fdfr.score > 100)
580  {
581  fdfr.score = 100;
582  }
583 
584  // BUT if step is of order few*MADslope*dx, then probably a false
585  // positive
586  if (fdfr.score == 100 &&
587  ::fabs(fdfr.step) < 3 * madSlope * fdfr.dx)
588  {
589  // if(debug)
590  // std::cout << "FDFa: F+ slip (|diff| < 3*madSlope*dx) at
591  // index "
592  //<< Avec[j].index << std::fixed << std::setprecision(osp)
593  //<< ": " << Avec[j].diff << " < 3 * " << madSlope
594  //<< " * " << fdfr.dx << " = " << 3*madSlope*fdfr.dx <<
595  //std::endl;
596  fdfr.score = -100;
597  }
598 
599  // save the hit
600  if (doSmall || fdfr.score == 100)
601  {
602  results.push_back(fdfr);
603  }
604  }
605 
606  else if (int(i) <= 2 * Nw - 2 && n1st >= 0)
607  { // first <Nwind pts outliers
608  // if(debug) std::cout << "FDFa: isBad at small i " << i <<
609  // std::endl; if(debug) for(int n=0; n<n1st; n++)
610  // std::cout << "FDFa OUT " << Avec[n].index << " "
611  // << xdata[Avec[n].index] << " small i " << i <<
612  // std::endl;
613  FilterHit<double> fdfr;
615  fdfr.index = Avec[0].index;
616  fdfr.npts = n1st;
617  fdfr.dx = xdata[Avec[n1st].index] - xdata[Avec[0].index];
618  results.push_back(fdfr);
619  }
620 
621  isBad = false;
622  nbad = 0;
623  }
624  }
625 
626  // catch outliers at the very end
627  if (isBad)
628  { // bad at the very end
629  // if(debug) for(j=bad0; j<Avec.size(); j++)
630  // std::cout << "FDFa: OUT " << Avec[j].index
631  // << " " << xdata[Avec[j].index] << std::endl;
632  j = bad0;
633  FilterHit<double> fdfr;
635  fdfr.index = Avec[j].index;
636  fdfr.npts = Avec.size() - j;
637  fdfr.dx = xdata[Avec[Avec.size() - 1].index] - xdata[Avec[j].index];
638  results.push_back(fdfr);
639  }
640 
641  return results.size();
642 
643  } // end FDiffFilter::analysis()
644 
645  //---------------------------------------------------------------------------------
646  template <class T>
647  void FDiffFilter<T>::dump(std::ostream& os, std::string tag)
648  {
649  size_t i, j, k, iprev;
650  int w(osw > 5 ? osw + 1 : 5);
651  os << "#" << tag << " FDiffFilter::dump() with limit " << std::fixed
652  << std::setprecision(osp) << fdlim << " sigma limit " << siglim
653  << std::setprecision(osp + 2) << " med,mad slope " << medSlope << " "
654  << madSlope << std::setprecision(osp)
655  << (noxdata ? " (xdata is index)" : "") << "\n#" << tag << " "
656  << std::setw(2) << "i"
657  << " " << std::setw(w) << "xd"
658  << " " << std::setw(3) << "flg"
659  << " " << std::setw(w) << "data"
660  << " " << std::setw(w) << "fdif"
661  << " " << std::setw(w) << "sig"
662  << " " << std::setw(w) << "slope"
663  << " " << std::setw(w) << "slp_u"
664  << " " << std::setw(w) << "sl*dx"
665  << " " << std::setw(w) << "slu*dx"
666  << " " << std::setw(5)
667  << "dx"
668  //<< " " << std::setw(w) << "sigslope*dx"
669  << std::endl;
670 
671  T dt(0);
672  std::string sdif, ssig, sldx, slop, slou, sludx; //,sigslo;
673  const size_t N(Avec.size());
674  for (i = 0, j = 0, k = 0, iprev = -1; i < ilimit; i++)
675  {
676  // find j where Avec[j].index == i
677  while (j < N && Avec[j].index < i)
678  j++;
679  bool haveAvec(Avec[j].index == i);
680  if (haveAvec)
681  {
682  sdif = gnsstk::StringUtils::asString(Avec[j].diff, osp);
683  ssig = gnsstk::StringUtils::asString(Avec[j].sigN, osp);
684  if (iprev > -1)
685  {
686  dt = (noxdata ? T(i - iprev) : xdata[i] - xdata[iprev]);
687  }
688  slop = gnsstk::StringUtils::asString(Avec[j].sloN, osp);
689  slou = gnsstk::StringUtils::asString(Avec[Avec[j].sloInd].sloN, osp);
690  sldx = gnsstk::StringUtils::asString(Avec[j].sloN * dt, osp);
691  sludx = gnsstk::StringUtils::asString(Avec[Avec[j].sloInd].sloN * dt,
692  osp);
693  // sigslo = gnsstk::StringUtils::asString(madSlope*dt,osp);
694  }
695  else
696  {
697  sdif = ssig = sldx = sludx = slou = "?"; // sigslo = "?";
698  }
699  os << tag << std::fixed << std::setprecision(osp) << " "
700  << std::setw(3) << i << " " << std::setw(w)
701  << (noxdata ? T(i) : xdata[i]) << " " << std::setw(3)
702  << (noflags ? 0 : flags[i]) << " " << std::setw(w) << data[i] << " "
703  << std::setw(w) << sdif << " " << std::setw(w) << ssig << " "
704  << std::setw(w) << slop << " " << std::setw(w) << slou << " "
705  << std::setw(w) << sldx << " " << std::setw(w) << sludx << " "
706  << std::setprecision(2) << std::setw(5)
707  << dt
708  //<< " " << std::setw(w) << sigslo
709  << (haveAvec && Avec[j].sigN > siglim ? " SIG" : "")
710  << (haveAvec ? "" : " NA");
711  if (k < results.size() && haveAvec && i == results[k].index)
712  {
713  os << " " << results[k].asString()
714  << (results[k].type == FilterHit<T>::slip &&
715  results[k].score < 100
716  ? " SMALL"
717  : "");
718  k++;
719  }
720  os << std::endl;
721  if (haveAvec)
722  {
723  iprev = Avec[j].index;
724  }
725  }
726  } // end FDiffFilter<T>::dump()
727 
728  //---------------------------------------------------------------------------------
729  //---------------------------------------------------------------------------------
734  template <class T> class IterativeFDiffFilter
735  {
736  private:
738  std::vector<FilterHit<T>> results;
739 
740  // member data ---------------------------------------
741  // first those passes to FDiffFilter
742  int osw, osp;
743 
744  const std::vector<T>
745  &xdata;
746  const std::vector<T>
747  &data;
748  const std::vector<int>
749  &flags;
750 
751  T fdlim;
752  T siglim;
753  unsigned int Nwind;
754  unsigned int Nsig;
755  bool doSmall;
756 
757  // and those unique to this class
758  unsigned int itermax;
760  std::ostream &logstrm;
761  bool resetSigma;
762  T siguse;
764  std::vector<unsigned int>
766  bool verbose;
767  std::string label;
768 
769  public:
770  // member functions ---------------------------------------
781  IterativeFDiffFilter(const std::vector<T>& x, const std::vector<T>& d,
782  const std::vector<int>& f,
783  std::ostream& os = std::cout)
784  : data(d), xdata(x), flags(f), logstrm(os)
785  {
786  keepSigIndex = resetSigma = verbose = false;
787  doSmall = true;
788  itermax = 3;
789  label = std::string();
790  // rest are defaults of FDiffFilter
791  FDiffFilter<T> fdf(x, d, f);
792  osw = fdf.osw;
793  osp = fdf.osp;
794  }
795 
797  inline void setWidth(unsigned int w) { Nwind = w; }
798 
800  inline unsigned int getWidth() { return Nwind; }
801 
803  inline void setLimit(T val) { fdlim = val; }
804 
806  inline T getLimit() { return fdlim; }
807 
809  inline void setSigma(T val) { siglim = val; }
810 
812  inline T getSigma() { return siglim; }
813 
815  inline bool doSmallSlips(bool doit)
816  {
817  doSmall = doit;
818  return doit;
819  }
820 
822  inline bool doSmallSlips() { return doSmall; }
823 
825  inline bool doResetSigma(bool doit)
826  {
827  resetSigma = doit;
828  return doit;
829  }
830 
832  inline bool indexHighSigmas(bool doit)
833  {
834  keepSigIndex = doit;
835  return doit;
836  }
837 
839  inline bool indexingHighSigmas() { return keepSigIndex; }
840 
842  inline bool doVerbose(bool doit)
843  {
844  verbose = doit;
845  return doit;
846  }
847 
849  inline void setLabel(const std::string doit) { label = doit; }
850 
852  inline std::string getLabel() { return label; }
853 
855  inline void setw(int w) { osw = w; }
856 
858  inline void setprecision(int p) { osp = p; }
859 
861  inline T getEstimatedSigmaLimit() { return Esiglim; }
862 
864  inline T getUsedSigmaLimit() { return siguse; }
865 
867  std::vector<FilterHit<T>> getResults() { return results; }
868 
870  inline unsigned int getNhighSigma() { return Nsig; }
871 
873  inline std::vector<unsigned int> getHighSigmaIndex()
874  {
875  return sigIndexes;
876  }
877 
889  int analysis();
890 
903  int editArrays(std::vector<T>& data, std::vector<int>& flags,
904  bool doInt = true, const int badFlag = 1);
905 
906  }; // end class IterativeFDiffFilter
907 
908  //---------------------------------------------------------------------------------
913  template <class T> int IterativeFDiffFilter<T>::analysis()
914  {
915  // size of the data arrays
916  const unsigned int size(xdata.size() < data.size() ? xdata.size()
917  : data.size());
918  if (size <= 2)
919  {
920  return -1;
921  }
922 
923  // save all results in each iteration; use results during each iteration
924  std::vector<std::vector<FilterHit<T>>> Results;
925 
926  // handle input data ---------------------------------
927  // use a copy of the data within the iteration loop
928  std::vector<T> Tdata(data);
929  // copy flags, create if needed
930  std::vector<int> Tflags;
931  if (flags.size() < size)
932  {
933  Tflags = std::vector<int>(size, 0);
934  }
935  else
936  {
937  Tflags = std::vector<int>(flags);
938  }
939 
940  // analysis ------------------------------------------
941  unsigned int iter, i, j, k, nr(0);
942  siguse = siglim;
943 
944  // iterate over (filter / compute new sigma limit / analysis)
945  iter = 1;
946  while (iter <= itermax)
947  {
948  // must redefine filter each time since arrays (const in fdf) change
949  FDiffFilter<T> fdf(xdata, Tdata, Tflags);
950  fdf.setWidth(Nwind); // fdf.Nwind
951  fdf.setLimit(fdlim); // fdf.fdlim
952  fdf.setSigma(siguse); // fdf.siglim
953  fdf.setprecision(osp); // fdf.osp
954  fdf.setw(osw); // fdf.osw
955  fdf.doSmallSlips(doSmall); // fdf.doSmall
956  fdf.indexHighSigmas(iter == itermax && keepSigIndex);
957 
958  // filter the data -----------
959  i = fdf.filter();
960  // if(verbose) logstrm << "# " << label << " filter returned " << i <<
961  // std::endl;
962  if (i <= 2)
963  {
964  logstrm << "Not enough data, abort.\n";
965  return -1;
966  }
967 
968  if (iter == itermax && keepSigIndex)
969  {
970  sigIndexes = fdf.getHighSigmaIndex();
971  }
972 
973  // compute outlier limit from robust stats, and count outliers
974  int N;
975  fdf.computeRobustSigmaLimit(N, Esiglim);
976  if (verbose)
977  {
978  logstrm << "# " << label << " Estimated sigma limit " << std::fixed
979  << std::setprecision(osp) << Esiglim
980  << " and used sigma limit " << siguse << " (input was "
981  << siglim << ") with " << N << " hi-sigma points "
982  << std::endl;
983  }
984 
985  // reset sigma limit in filter, but not if its too large
986  // Esiglim/siglim < 3.0 // not too big
987  // Esiglim/siglim > 0.1 // not too small
988  if (resetSigma)
989  {
990  if (Esiglim > siglim)
991  {
992  if (Esiglim / siglim < 3.0)
993  {
994  siguse = Esiglim;
995  }
996  else
997  {
998  siguse = 3 * siglim;
999  }
1000  }
1001  else if (Esiglim < siglim)
1002  {
1003  if (Esiglim / siglim > 0.1)
1004  {
1005  siguse = Esiglim;
1006  }
1007  else
1008  {
1009  siguse = 0.1 * siglim;
1010  }
1011  }
1012  fdf.setSigma(siguse); // use the new sigma limit
1013  }
1014 
1015  // analysis ------------------
1016  fdf.analysis(); // get the outliers and slips
1017 
1018  // consider results ----------
1019  results = fdf.getResults();
1020  std::vector<unsigned int>
1021  eraseIndex; // index in results[] to be erased
1022 
1023  // loop over results: mark duplicates to be erased, mark outliers, fix
1024  // slips
1025  for (i = 0; i < results.size(); i++)
1026  {
1027  if (verbose)
1028  {
1029  logstrm << "# " << label << " Result " << ++nr << std::fixed
1030  << std::setprecision(osp) << " "
1031  << xdata[results[i].index] << " "
1032  << results[i].asString(osp) << std::endl;
1033  }
1034 
1035  // mark outliers
1036  if (results[i].type == FilterHit<T>::outlier)
1037  {
1038  k = results[i].index;
1039  for (j = 0; j < results[i].npts; j++)
1040  Tflags[k + j] = 1;
1041  }
1042 
1043  // slips: handle duplicates, and edit data
1044  if (results[i].type == FilterHit<T>::slip)
1045  {
1046 
1047  // search previous results, if they exist, for duplicate slips
1048  bool skip(false);
1049  for (k = 0; k < Results.size(); k++)
1050  {
1051 
1052  for (j = 0; j < Results[k].size(); j++)
1053  { // loop over prev results
1054  FilterHit<T> &oldres(Results[k][j]);
1055 
1056  if (oldres.type != FilterHit<T>::slip) // not a slip
1057  {
1058  continue;
1059  }
1060  if (results[i].index != oldres.index) // different index
1061  {
1062  continue;
1063  }
1064 
1065  // if both slips are non-small: add new to previous and
1066  // delete new
1067  if (results[i].score == 100 && oldres.score == 100)
1068  {
1069  // logstrm << " Combine slips " <<
1070  // results[i].asString(osp)
1071  // << " and " << oldres.asString(osp) << std::endl;
1072  T step = oldres.step + results[i].step;
1073  oldres.step = step;
1074  // keep the later sigma - outliers have been removed
1075  oldres.sigma = results[i].sigma;
1076  oldres.score =
1077  (unsigned int)(0.5 + 100. * ::fabs(step) / fdlim);
1078  if (oldres.score > 100)
1079  {
1080  oldres.score = 100;
1081  }
1082  // logstrm << " New combined slip is "
1083  // << oldres.asString(osp) << std::endl;
1084  }
1085 
1086  // if both slips are small, they should be identical =>
1087  // delete new
1088  // ...so, if only one is small, go on
1089  else if (results[i].score == 100 || oldres.score == 100)
1090  {
1091  continue;
1092  }
1093 
1094  // else both are small: delete new result
1095  skip = true;
1096  break;
1097  }
1098  }
1099 
1100  // save the index, to be deleted later
1101  if (skip)
1102  {
1103  eraseIndex.push_back(i);
1104  continue;
1105  }
1106 
1107  // if slip is too small to fix, go on
1108  if (::fabs(results[i].step) < fdlim)
1109  {
1110  // if(verbose) logstrm << "# " << label << " Slip too small: "
1111  // << std::fixed << std::setprecision(osp) << results[i].step
1112  //<< " < " << fdlim << std::endl;
1113  continue;
1114  }
1115 
1116  // fix the slip in the Tdata
1117  int islip(results[i].step +
1118  (results[i].step >= 0.0 ? 0.5 : -0.5));
1119  if (islip)
1120  {
1121  if (verbose)
1122  {
1123  logstrm << "# " << label << " Fix slip " << islip << " "
1124  << results[i].asString(osp) << std::endl;
1125  }
1126 
1127  // NB if slips in Tdata not fixed, its going to affect later
1128  // runs of the analysis
1129  for (j = results[i].index; j < Tdata.size(); j++)
1130  Tdata[j] -= islip;
1131  }
1132  } // end if slip
1133 
1134  } // end loop over results
1135 
1136  // erase marked slips
1137  if (eraseIndex.size() > 0)
1138  {
1139  // sort(eraseIndex.begin(),eraseIndex.end());
1140  for (i = eraseIndex.size() - 1; i >= 0; i--)
1141  {
1142  // logstrm << " Erase " << results[eraseIndex[i]].asString(osp)
1143  //<< std::endl;
1144  results.erase(results.begin() + eraseIndex[i]); // erase vector
1145  if (i == 0)
1146  {
1147  break; // i is unsigned
1148  }
1149  }
1150  }
1151 
1152  // save to Results
1153  Nsig = fdf.getNhighSigma();
1154  Results.push_back(results);
1155  results.clear();
1156 
1157  // dump this analysis
1158  if (verbose)
1159  {
1160  fdf.dump(logstrm,
1161  "FIX" + gnsstk::StringUtils::asString(iter - 1) + label);
1162  }
1163 
1164  ++iter; // next iteration
1165 
1166  } // end iteration loop
1167 
1168  // copy all Results into results
1169  results.clear();
1170  for (k = 0; k < Results.size(); k++)
1171  for (j = 0; j < Results[k].size(); j++)
1172  results.push_back(Results[k][j]);
1173 
1174  // scan for remaining small slips (result of combination of two large)
1175  if (!doSmall)
1176  {
1177  std::vector<unsigned int>
1178  eraseIndex; // index in results[] to be erased
1179  for (i = 0; i < results.size(); i++)
1180  {
1181  if (results[i].type != FilterHit<T>::slip)
1182  {
1183  continue;
1184  }
1185  // logstrm << " Final check " << results[i].asString(osp) <<
1186  // std::endl;
1187  if (results[i].score == 100)
1188  {
1189  continue;
1190  }
1191  eraseIndex.push_back(i);
1192  } // end loop over results
1193  if (eraseIndex.size() > 0)
1194  {
1195  for (i = eraseIndex.size() - 1; i >= 0; i--)
1196  {
1197  // logstrm << " Final Erase " <<
1198  // results[eraseIndex[i]].asString(osp)
1199  //<< std::endl;
1200  results.erase(results.begin() + eraseIndex[i]); // erase vector
1201  if (i == 0)
1202  {
1203  break; // i is unsigned
1204  }
1205  }
1206  }
1207  // logstrm << " End Final check" << std::endl;
1208  }
1209 
1210  return results.size();
1211  } // end IterativeFDiffFilter::analysis()
1212 
1213  //---------------------------------------------------------------------------------
1214  template <class T>
1216  std::vector<int>& flags,
1217  bool doInt, const int badFlag)
1218  {
1219  int nedit(0);
1220  unsigned int i, j, n;
1221 
1222  for (i = 0; i < results.size(); i++)
1223  {
1224  if (results[i].type == FilterHit<T>::BOD ||
1225  results[i].type == FilterHit<T>::other)
1226  {
1227  continue;
1228  }
1229 
1230  else if (results[i].type == FilterHit<T>::outlier)
1231  {
1232  j = results[i].index;
1233  // TD should this loop account for flags[j] already set?
1234  for (n = 0; n < results[i].npts; nedit++, n++, j++)
1235  flags[j] = badFlag;
1236  }
1237 
1238  else if (results[i].type == FilterHit<T>::slip)
1239  {
1240  double slip(results[i].step);
1241  if (doInt)
1242  {
1243  int islip(slip + (slip >= 0.0 ? 0.5 : -0.5));
1244  if (islip == 0)
1245  {
1246  continue;
1247  }
1248  slip = double(islip);
1249  }
1250  for (j = results[i].index; j < data.size(); j++)
1251  data[j] -= slip;
1252  nedit++;
1253  }
1254  }
1255 
1256  return nedit;
1257  } // end int IterativeFDiffFilter::editArrays()
1258 
1259  //---------------------------------------------------------------------------------
1260  //---------------------------------------------------------------------------------
1261 } // namespace gnsstk
1262 #endif // #define FDIFF_FILTER_INCLUDE
gnsstk::IterativeFDiffFilter::IterativeFDiffFilter
IterativeFDiffFilter(const std::vector< T > &x, const std::vector< T > &d, const std::vector< int > &f, std::ostream &os=std::cout)
Definition: FDiffFilter.hpp:781
gnsstk::FDiffFilter::keepSigIndex
bool keepSigIndex
if true, keep vector of HighSigmaIndex
Definition: FDiffFilter.hpp:188
gnsstk::FilterHit::index
unsigned int index
index in the data array(s) at which this event occurs
Definition: StatsFilterHit.hpp:91
gnsstk::IterativeFDiffFilter::Nsig
unsigned int Nsig
filter()'s count of high sigma - analysis needed
Definition: FDiffFilter.hpp:754
gnsstk::FDiffFilter::setLimit
void setLimit(T val)
set the limit
Definition: FDiffFilter.hpp:228
logstrm
ofstream logstrm
Definition: testSSEph.cpp:87
gnsstk::IterativeFDiffFilter::setw
void setw(int w)
set width for dump
Definition: FDiffFilter.hpp:855
gnsstk::TwoSampleStats::Add
void Add(const T &x, const T &y)
Definition: Stats.hpp:867
gnsstk::IterativeFDiffFilter::flags
const std::vector< int > & flags
reference to flags, parallel to data, 0 == good
Definition: FDiffFilter.hpp:749
gnsstk::FDiffFilter::setprecision
void setprecision(int p)
set precision for output
Definition: FDiffFilter.hpp:263
gnsstk::FDiffFilter::noflags
bool noflags
true when flags array is not given
Definition: FDiffFilter.hpp:173
StringUtils.hpp
gnsstk::IterativeFDiffFilter::getHighSigmaIndex
std::vector< unsigned int > getHighSigmaIndex()
get the indexes of high-sigma points (only if indexHighSigmas(true))
Definition: FDiffFilter.hpp:873
gnsstk::TwoSampleStats::Slope
T Slope(void) const
return slope of best-fit line Y=slope*X + intercept
Definition: Stats.hpp:1060
gnsstk::FDiffFilter::fdlim
T fdlim
|first diff| must be > this to be outlier/slip
Definition: FDiffFilter.hpp:182
gnsstk::IterativeFDiffFilter::data
const std::vector< T > & data
reference to data to be filtered
Definition: FDiffFilter.hpp:747
gnsstk::FDiffFilter::getHighSigmaIndex
std::vector< unsigned int > getHighSigmaIndex()
get the indexes of high-sigma points (only if indexHighSigmas(true))
Definition: FDiffFilter.hpp:273
gnsstk::IterativeFDiffFilter::indexingHighSigmas
bool indexingHighSigmas()
get indexing flag
Definition: FDiffFilter.hpp:839
gnsstk::IterativeFDiffFilter
forward declaration
Definition: FDiffFilter.hpp:113
gnsstk::FDiffFilter::osw
int osw
Definition: FDiffFilter.hpp:171
gnsstk::TwoSampleStats::StdDevY
T StdDevY(void) const
return computed Y standard deviation
Definition: Stats.hpp:1057
gnsstk::IterativeFDiffFilter::getLimit
T getLimit()
get limit
Definition: FDiffFilter.hpp:806
gnsstk::IterativeFDiffFilter::getNhighSigma
unsigned int getNhighSigma()
get the number of remaining high-sigma points after analysis()
Definition: FDiffFilter.hpp:870
gnsstk::IterativeFDiffFilter::setprecision
void setprecision(int p)
set precision for dump
Definition: FDiffFilter.hpp:858
gnsstk::IterativeFDiffFilter::fdlim
T fdlim
|first diff| must be > this to be outlier/slip
Definition: FDiffFilter.hpp:751
gnsstk::FDiffFilter::flags
const std::vector< int > & flags
reference to flags, parallel to data, 0 == good
Definition: FDiffFilter.hpp:179
gnsstk::FDiffFilter::Nwind
unsigned int Nwind
size of sliding window
Definition: FDiffFilter.hpp:185
gnsstk::FDiffFilter::indexHighSigmas
bool indexHighSigmas(bool doit)
set the indexing flag
Definition: FDiffFilter.hpp:250
gnsstk::IterativeFDiffFilter::siguse
T siguse
sigma limit used in last iteration
Definition: FDiffFilter.hpp:762
gnsstk::StringUtils::asString
std::string asString(IonexStoreStrategy e)
Convert a IonexStoreStrategy to a whitespace-free string name.
Definition: IonexStoreStrategy.cpp:46
gnsstk::IterativeFDiffFilter::verbose
bool verbose
output comments and dump FDiffFilters
Definition: FDiffFilter.hpp:766
gnsstk::IterativeFDiffFilter::setLimit
void setLimit(T val)
set limit
Definition: FDiffFilter.hpp:803
gnsstk::IterativeFDiffFilter::keepSigIndex
bool keepSigIndex
if true, keep vector of HighSigmaIndex
Definition: FDiffFilter.hpp:763
gnsstk::IterativeFDiffFilter::getWidth
unsigned int getWidth()
get window width
Definition: FDiffFilter.hpp:800
gnsstk::IterativeFDiffFilter::doSmall
bool doSmall
if true, include small slips (<fdlim) in results
Definition: FDiffFilter.hpp:755
gnsstk::FDiffFilter::sigIndexes
std::vector< unsigned int > sigIndexes
saved indexes of Nsig high sigma pts
Definition: FDiffFilter.hpp:190
gnsstk::TwoSampleStats::Subtract
void Subtract(const T &x, const T &y)
Definition: Stats.hpp:879
gnsstk::Robust::Quartiles
void Quartiles(const T *xd, const int nd, T &Q1, T &Q3)
Definition: RobustStats.hpp:425
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::IterativeFDiffFilter::results
std::vector< FilterHit< T > > results
vector of results of the iterative analysis
Definition: FDiffFilter.hpp:738
gnsstk::IterativeFDiffFilter::osw
int osw
Definition: FDiffFilter.hpp:742
gnsstk::IterativeFDiffFilter::setSigma
void setSigma(T val)
set sigma limit
Definition: FDiffFilter.hpp:809
gnsstk::FDiffFilter::Esiglim
T Esiglim
compute siglim (= robust outlier limit)
Definition: FDiffFilter.hpp:184
gnsstk::IterativeFDiffFilter::label
std::string label
put on output lines when verbose
Definition: FDiffFilter.hpp:767
Stats.hpp
gnsstk::FDiffFilter::Analysis::sloInd
int sloInd
index in Avec of slope used in current calc. of diff
Definition: FDiffFilter.hpp:157
gnsstk::FDiffFilter::getLimit
T getLimit()
get the limit
Definition: FDiffFilter.hpp:231
gnsstk::FDiffFilter::noxdata
bool noxdata
true when xdata is not given
Definition: FDiffFilter.hpp:172
gnsstk::IterativeFDiffFilter::doVerbose
bool doVerbose(bool doit)
make output verbose
Definition: FDiffFilter.hpp:842
gnsstk::FilterHit::score
unsigned int score
weight of slip (=100)
Definition: StatsFilterHit.hpp:96
gnsstk::IterativeFDiffFilter::getUsedSigmaLimit
T getUsedSigmaLimit()
get sigma limit used in last iteration
Definition: FDiffFilter.hpp:864
gnsstk::FDiffFilter::computeRobustSigmaLimit
void computeRobustSigmaLimit(int &N, T &new_siglim)
Definition: FDiffFilter.hpp:457
gnsstk::IterativeFDiffFilter::getSigma
T getSigma()
get sigma limit
Definition: FDiffFilter.hpp:812
gnsstk::FDiffFilter::ilimit
int ilimit
largest allowed index in data[] is ilimit-1
Definition: FDiffFilter.hpp:180
gnsstk::FDiffFilter::osp
int osp
width and precision for dump(), (default 8,3)
Definition: FDiffFilter.hpp:171
gnsstk::FDiffFilter::FDiffFilter
FDiffFilter(const std::vector< T > &x, const std::vector< T > &d, const std::vector< int > &f)
Definition: FDiffFilter.hpp:205
gnsstk::IterativeFDiffFilter::Esiglim
T Esiglim
Estimated sigma limit computed from robust stats.
Definition: FDiffFilter.hpp:759
gnsstk::FDiffFilter::setWidth
void setWidth(unsigned int w)
set the width of the window
Definition: FDiffFilter.hpp:222
gnsstk::FDiffFilter
Definition: FDiffFilter.hpp:131
gnsstk::FDiffFilter::xdata
const std::vector< T > & xdata
reference to xdata - 'time'; if empty use count
Definition: FDiffFilter.hpp:176
gnsstk::FDiffFilter::setw
void setw(int w)
set width for output
Definition: FDiffFilter.hpp:260
gnsstk::IterativeFDiffFilter::analysis
int analysis()
Definition: FDiffFilter.hpp:913
gnsstk::FDiffFilter::setSigma
void setSigma(T val)
set the sigma
Definition: FDiffFilter.hpp:234
gnsstk::IterativeFDiffFilter::Nwind
unsigned int Nwind
size of sliding window
Definition: FDiffFilter.hpp:753
gnsstk::IterativeFDiffFilter::editArrays
int editArrays(std::vector< T > &data, std::vector< int > &flags, bool doInt=true, const int badFlag=1)
Definition: FDiffFilter.hpp:1215
gnsstk::FDiffFilter::doSmallSlips
bool doSmallSlips(bool doit)
set the 'small slips' limit
Definition: FDiffFilter.hpp:240
gnsstk::FilterHit::npts
unsigned int npts
number data points in segment (= a delta index)
Definition: StatsFilterHit.hpp:93
gnsstk::FDiffFilter::medSlope
T medSlope
Definition: FDiffFilter.hpp:192
gnsstk::FDiffFilter::results
std::vector< FilterHit< T > > results
vector of results of analysis()
Definition: FDiffFilter.hpp:168
gnsstk::FDiffFilter::doSmallSlips
bool doSmallSlips()
get the 'small slips' limit
Definition: FDiffFilter.hpp:247
gnsstk::IterativeFDiffFilter::getEstimatedSigmaLimit
T getEstimatedSigmaLimit()
get computed sigma limit (= robust outlier limit) after analysis()
Definition: FDiffFilter.hpp:861
gnsstk::FDiffFilter::getWidth
unsigned int getWidth()
get the width of the window
Definition: FDiffFilter.hpp:225
gnsstk::FDiffFilter::Analysis::diff
T diff
first difference = data[index]-data[index-1]
Definition: FDiffFilter.hpp:154
RobustStats.hpp
example3.data
data
Definition: example3.py:22
gnsstk::FDiffFilter::analysis
int analysis()
Definition: FDiffFilter.hpp:494
gnsstk::FDiffFilter::madSlope
T madSlope
robust stats on slope
Definition: FDiffFilter.hpp:192
gnsstk::IterativeFDiffFilter::getLabel
std::string getLabel()
get the label in dump
Definition: FDiffFilter.hpp:852
StatsFilterHit.hpp
gnsstk::FDiffFilter::Avec
std::vector< Analysis > Avec
Definition: FDiffFilter.hpp:165
gnsstk::FDiffFilter::Nsig
unsigned int Nsig
filter()'s count of high sigma - analysis needed
Definition: FDiffFilter.hpp:186
gnsstk::FDiffFilter::Analysis::sigN
T sigN
sigmaYX for N pts of first diff ending at index
Definition: FDiffFilter.hpp:155
gnsstk::IterativeFDiffFilter::itermax
unsigned int itermax
maximum number of itertions (3)
Definition: FDiffFilter.hpp:758
gnsstk::QSort
void QSort(T *sa, int na, int(*comp)(const T &, const T &)=gnsstk::Qsort_compare)
Definition: RobustStats.hpp:139
gnsstk::FDiffFilter::dump
void dump(std::ostream &s, std::string tag=std::string())
Definition: FDiffFilter.hpp:647
gnsstk::FDiffFilter::Analysis::index
unsigned int index
index in original arrays to which this info applies.
Definition: FDiffFilter.hpp:153
gnsstk::FDiffFilter::Analysis::sloN
T sloN
2-sample slope of data for N pts ending at index
Definition: FDiffFilter.hpp:156
gnsstk::IterativeFDiffFilter::logstrm
std::ostream & logstrm
write to output stream
Definition: FDiffFilter.hpp:760
gnsstk::FilterHit::step
T step
for a slip, an estimate of the step in the data
Definition: StatsFilterHit.hpp:98
gnsstk::FDiffFilter::data
const std::vector< T > & data
reference to data to be filtered
Definition: FDiffFilter.hpp:177
gnsstk::TwoSampleStats::N
unsigned int N(void) const
Definition: Stats.hpp:1037
gnsstk::FDiffFilter::siglim
T siglim
sigma > this indicates possible outlier/slip
Definition: FDiffFilter.hpp:183
gnsstk::IterativeFDiffFilter::sigIndexes
std::vector< unsigned int > sigIndexes
saved indexes of Nsig high sigma pts
Definition: FDiffFilter.hpp:765
gnsstk::FilterHit::type
event type
type of event: BOD, outlier(s), slip, other
Definition: StatsFilterHit.hpp:88
gnsstk::IterativeFDiffFilter::resetSigma
bool resetSigma
if true, set siglim to Esiglim in each iteration
Definition: FDiffFilter.hpp:761
gnsstk::IterativeFDiffFilter::indexHighSigmas
bool indexHighSigmas(bool doit)
set indexing flag
Definition: FDiffFilter.hpp:832
gnsstk::IterativeFDiffFilter::doSmallSlips
bool doSmallSlips(bool doit)
set flag to do small slips
Definition: FDiffFilter.hpp:815
gnsstk::FilterHit::dx
T dx
step in xdata: before SLIP or after OUT
Definition: StatsFilterHit.hpp:100
gnsstk::IterativeFDiffFilter::xdata
const std::vector< T > & xdata
reference to xdata - 'time'; if empty use count
Definition: FDiffFilter.hpp:745
gnsstk::FilterHit
Definition: StatsFilterHit.hpp:68
gnsstk::FilterHit::sigma
T sigma
for a slip, RSS future and past sigma on the data
Definition: StatsFilterHit.hpp:99
gnsstk::FDiffFilter::doSmall
bool doSmall
if true, include small slips (<fdlim) in results
Definition: FDiffFilter.hpp:187
gnsstk::IterativeFDiffFilter::getResults
std::vector< FilterHit< T > > getResults()
get results vector of FilterHit
Definition: FDiffFilter.hpp:867
gnsstk::IterativeFDiffFilter::osp
int osp
width and precision for dump(), (default 8,3)
Definition: FDiffFilter.hpp:742
gnsstk::TwoSampleStats
Definition: Stats.hpp:126
gnsstk::IterativeFDiffFilter::doResetSigma
bool doResetSigma(bool doit)
(re)set sigma limit
Definition: FDiffFilter.hpp:825
gnsstk::IterativeFDiffFilter::doSmallSlips
bool doSmallSlips()
get flag to do small slips
Definition: FDiffFilter.hpp:822
gnsstk::FDiffFilter::getNhighSigma
unsigned int getNhighSigma()
Definition: FDiffFilter.hpp:270
gnsstk::FDiffFilter::filter
int filter(const size_t index=0, int npts=-1)
Definition: FDiffFilter.hpp:317
gnsstk::IterativeFDiffFilter::setWidth
void setWidth(unsigned int w)
set window width
Definition: FDiffFilter.hpp:797
gnsstk::FDiffFilter::Analysis
Definition: FDiffFilter.hpp:141
gnsstk::IterativeFDiffFilter::setLabel
void setLabel(const std::string doit)
define the label in dump
Definition: FDiffFilter.hpp:849
gnsstk::IterativeFDiffFilter::siglim
T siglim
sigma > this indicates possible outlier/slip
Definition: FDiffFilter.hpp:752
gnsstk::FDiffFilter::getResults
std::vector< FilterHit< T > > getResults()
get results vector of FilterHit
Definition: FDiffFilter.hpp:266
gnsstk::FDiffFilter::getSigma
T getSigma()
get the sigma
Definition: FDiffFilter.hpp:237
gnsstk::FDiffFilter::Analysis::Analysis
Analysis()
constructor
Definition: FDiffFilter.hpp:145
gnsstk::Robust::MedianAbsoluteDeviation
T MedianAbsoluteDeviation(T *xd, int nd, T &M, bool save_flag=true)
Definition: RobustStats.hpp:467
gnsstk::FDiffFilter::indexingHighSigmas
bool indexingHighSigmas()
get the indexing flag
Definition: FDiffFilter.hpp:257


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