WindowFilter.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 
39 #ifndef GNSSTK_WINDOWFILTER_HPP
40 #define GNSSTK_WINDOWFILTER_HPP
41 
93 #include "RobustStats.hpp"
94 #include "Stats.hpp"
95 #include <deque>
96 #include <vector>
97 //#include "StringUtils.hpp" // TEMP
98 //#include "logstream.hpp" // TEMP
99 
100 #include "StatsFilterHit.hpp"
101 
102 namespace gnsstk
103 {
108  template <class T> class FilterNearMiss
109  {
110  public:
112  FilterNearMiss() : index(-1), step(T(0)), score(0), msg(std::string()) {}
113 
114  int index;
115  int score;
116  T step;
117  T sigma;
118  std::string msg;
119 
120  }; // end class FilterNearMiss
121 
122  //---------------------------------------------------------------------------------
123  //---------------------------------------------------------------------------------
129  template <class T> class StatsFilterBase
130  {
131  public:
134 
136  virtual void Reset() = 0;
137 
139  virtual unsigned int N() const = 0;
140 
142  virtual void Add(const T& x, const T& y) = 0;
143 
145  virtual void Subtract(const T& x, const T& y) = 0;
146 
148  virtual T StdDev() const = 0;
149 
151  virtual T Variance() const = 0;
152 
154  virtual T Average() const = 0;
155 
157  virtual T Evaluate(T x) const = 0;
158 
163  virtual T Slope() const = 0;
164 
169  virtual T Intercept() const = 0;
170 
172  virtual std::string asString() const = 0;
173 
174  }; // end class StatsFilterBase
175 
177  template <class T> class OneSampleStatsFilter : public StatsFilterBase<T>
178  {
179  public:
182 
184  inline void Reset() { S.Reset(); }
185 
187  inline unsigned int N() const { return S.N(); }
188 
190  void Add(const T& x, const T& y) { S.Add(y); }
191 
193  void Subtract(const T& x, const T& y) { S.Subtract(y); }
194 
196  T StdDev() const { return S.StdDev(); }
197 
199  T Variance() const { return S.Variance(); }
200 
202  inline T Average() const { return S.Average(); }
203 
208  inline T Evaluate(T x) const { return S.Average(); }
209 
214  inline T Slope() const { return T(); }
215 
220  inline T Intercept() const { return S.Average(); }
221 
223  std::string asString() const { return S.asString(); }
224 
225  private:
227 
228  }; // end class OneSampleStatsFilter
229 
231  template <class T> class TwoSampleStatsFilter : public StatsFilterBase<T>
232  {
233  public:
236 
238  inline void Reset() { TSS.Reset(); }
239 
241  inline unsigned int N() const { return TSS.N(); }
242 
244  void Add(const T& x, const T& y) { TSS.Add(x, y); }
245 
247  void Subtract(const T& x, const T& y) { TSS.Subtract(x, y); }
248 
250  T StdDev() const
251  {
252  if (TSS.N() < 3)
253  {
254  return TSS.StdDevY(); // cheat a little
255  }
256  return TSS.SigmaYX();
257  }
258 
260  T Variance() const
261  {
262  if (TSS.N() < 3)
263  {
264  return TSS.VarianceY(); // cheat a little
265  }
266  return TSS.VarianceYX();
267  }
268 
270  inline T Average() const { return TSS.AverageY(); }
271 
273  inline T Evaluate(T x) const { return TSS.Evaluate(x); }
274 
276  inline T Slope() const { return TSS.Slope(); }
277 
279  inline T Intercept() const { return TSS.Intercept(); }
280 
282  std::string asString() const { return TSS.asString(); }
283 
284  private:
286 
287  }; // end class TwoSampleStatsFilter
288 
289  // end template <class T> class StatsFilterBase
290 
291  //---------------------------------------------------------------------------------
292  //---------------------------------------------------------------------------------
302  template <class T> class WindowFilter
303  {
304  public:
306  class Analysis
307  {
308  public:
310  Analysis() : pN(0), fN(0) {}
311 
312  // member data
313  unsigned int
315  T step;
316  T sigma;
317  // past stats
318  unsigned int pN;
319  T pave;
320  T psig;
321  // future stats
322  unsigned int fN;
323  T fave;
324  T fsig;
325  // T pslope; ///< (twoSample only) slope (ave p,f) in units
326  // data/xdata T fslope; ///< (twoSample only) slope (ave p,f)
327  // in units data/xdata
328  // results of analysis
329  // net result of analysis: -1,-2,-3,-4 (failure) or a percentage
330  // -1 near end; -2 small step; -3 small ratio; -4 marginal step &
331  // ratio;
332  int score;
333  std::string msg;
334 
335  }; // end class Analysis
336 
343  WindowFilter(const std::vector<T>& x, const std::vector<T>& d,
344  const std::vector<int>& f)
345  : xdata(x), data(d), flags(f)
346  {
347  width = 20;
348  twoSample = false;
349  minratio = T(2.0);
350  minstep = T(0.8);
351  minmargin = T(0.5);
352  pffrac = T(0.75);
353  halfwidth = 3;
354  buffsize = 0;
355  balanced = false;
356  fullwindows = false;
357  noxdata = (xdata.size() == 0);
358  noflags = (flags.size() == 0);
359  dumpNA = true;
360  dumpAmsg = false;
361  debug = false;
362  osw = 8;
363  osp = 3;
364  }
365 
366  // get and set filter configuration
367  inline void setWidth(int w) { width = w; }
368  inline void setBufferSize(int b) { buffsize = b; }
369  inline void setTwoSample(bool b) { twoSample = b; }
370  inline void setBalanced(bool b) { balanced = b; }
371  inline void setFullWindows(bool b) { fullwindows = b; }
372  inline int getWidth() { return width; }
373  inline int getBufferSize() { return buffsize; }
374  inline bool isTwoSample() { return twoSample; }
375  inline bool isOneSample() { return !twoSample; }
376  inline bool isBalanced() { return balanced; }
377  inline bool isFullWindows() { return fullwindows; }
378  // get and set analysis configuration
379  inline void setMinRatio(T val) { minratio = val; }
380  inline void setMinStep(T val) { minstep = val; }
381  inline void setMinMargin(T val) { minmargin = val; }
382  inline void setPFFrac(T val) { pffrac = val; }
383  inline void setHalfWidth(int hw) { halfwidth = hw; }
384  inline T getMinRatio() { return minratio; }
385  inline T getMinStep() { return minstep; }
386  inline T getMinMargin() { return minmargin; }
387  inline T getPFFrac() { return pffrac; }
388  inline int getHalfWidth() { return halfwidth; }
389 
394  inline void setDumpAnalMsg(bool b) { dumpAmsg = b; }
395  inline bool willDumpAnalMsg() { return dumpAmsg; }
397  inline void setDumpNoAnal(bool b) { dumpNA = b; }
398  inline bool willDumpNoAnal() { return dumpNA; }
400  inline void setDebug(bool b) { debug = b; }
401  inline bool getDebug() { return debug; }
402 
403  inline void setw(int w) { osw = w; }
404  inline void setprecision(int p) { osp = p; }
405 
407  std::vector<FilterHit<T>> getResults() { return results; }
408 
413  void reset() { analvec.clear(); }
414 
429  int filter(const size_t index = 0, int npts = -1);
430 
437  int analyze();
438 
444  void dump(std::ostream& s, std::string tag = std::string());
445 
446  // NB there should be another routine (outside this class) to get stats on
447  // the data within a segment
455  void getStats(FilterHit<T>& fe, bool noedge = true);
456 
457  private:
458  // member data
459  bool balanced;
460  bool fullwindows;
461  bool twoSample;
462  unsigned int width;
463  int buffsize;
464  bool noxdata;
465  bool noflags;
466 
467  unsigned int
472  T pffrac;
473 
474  const std::vector<T>
475  &xdata;
476  const std::vector<T> &data;
477  const std::vector<int>
478  &flags;
479 
480  int osw, osp;
481  bool dumpNA;
482  bool dumpAmsg;
483  bool debug;
484 
489  std::vector<Analysis> analvec;
490 
491  public:
496  std::vector<FilterHit<T>> results;
497 
498  // vector of FilterNearMiss, generated by analyze()
499  // std::vector< FilterNearMiss<T> > maybes;
500 
501  }; // end class WindowFilter
502 
503  //---------------------------------------------------------------------------------
504  // return number of analyzed points, else -1 too little data, -2 two sample
505  // w/o x, -3 too little x or flag data.
506  template <class T> int WindowFilter<T>::filter(const size_t i0, int dsize)
507  {
508  // number of points to filter
509  if (dsize == -1) // this bc can't use data.size() as a default arg
510  {
511  dsize = data.size() - i0 - buffsize;
512  }
513 
514  // largest index is ilimit-1
515  const int ilimit(dsize + i0);
516 
517  // validate input
518  // ----------------------------------------------------------- is there
519  // enough data to apply the filter? if not, return -1 if there are flags,
520  // count the good points
521  int i(i0), j;
522  unsigned int n(0);
523  if (!noflags)
524  {
525  while (i < ilimit && n < 2 * width + buffsize)
526  {
527  if (flags[i] == 0)
528  {
529  n++;
530  }
531  i++;
532  }
533  if (i == ilimit)
534  {
535  return -1;
536  }
537  }
538  else if (dsize < int(2 * width + buffsize))
539  {
540  return -1;
541  }
542 
543  // is xdata given? can't two-sample without x...
544  if (twoSample && noxdata)
545  {
546  return -2;
547  }
548 
549  // if xdata or flags is there, make sure its big enough
550  if (!noxdata && xdata.size() - i0 - buffsize < dsize)
551  {
552  return -3;
553  }
554  if (!noflags && flags.size() - i0 - buffsize < dsize)
555  {
556  return -3;
557  }
558 
559  // create stats for "past" and "future" sliding windows
560  // ---------------------
561  StatsFilterBase<T> *ptrPast, *ptrFuture;
562 
563  if (twoSample)
564  {
565  ptrPast = new TwoSampleStatsFilter<T>();
566  ptrFuture = new TwoSampleStatsFilter<T>();
567  }
568  else
569  {
570  ptrPast = new OneSampleStatsFilter<T>();
571  ptrFuture = new OneSampleStatsFilter<T>();
572  }
573 
574  // stick a little buffer, length buffsize, holding indexes, between past
575  // and future
576  std::deque<int> buff;
577 
578  // --------------------------------------------------------------------------
579  // Cartoon of the 'two-pane moving window'
580  // windows: 'past window' 'future window'
581  // stats : ----pastStats---- ----futureStats--
582  // data : (x x x x x x x x x)(x x x x x x x x x) x ...
583  // | | | |
584  // indexes: iminus i-1 i iplus
585  // at each step, move i from F to P, add iplus to F, subtract iminus from P
586  // --------------------------------------------------------------------------
587  // if balanced=F, at the begin(end), only the past(future) window will shrink.
588  // stats : -pastSt- ----futureStats--
589  // data : (x x x x)(x x x x x x x x x) x ...
590  // | | | |
591  // indexes: iminus i-1 i iplus
592  // So, at each step, move i from F to P;
593  // if(iplus < size-1) add 1 to F
594  // if(past.N()>=width) sub 1 from P
595  // else add 1 to F, sub 1 from P
596  // --------------------------------------------------------------------------
597  // if balanced=T, force the past and future windows to stay the same size
598  // start:
599  // i=1| |ip=2
600  // data: (x)(x) x ...
601  // |im=0 now move i from F to P, add 2 to F
602  // |i=2 |ip=4
603  // data: (x x)(x x) x ...
604  // |im=1 now move i from F to P, add 2 to F
605  // |i=3 |ip=6
606  // data: (x x x)(x x x) x ...
607  // |im=2 now move i from F to P, add 2 to F
608  // do this until P.N() = width
609  // --------------------------------------------------------------------------
610  // stop:
611  // data: (x x x x x x x x x)(x x x x x x x x x)
612  // |im |i |ip==size() now mv i F->P, P-2
613  // data: x x(x x x x x x x x)(x x x x x x x x)
614  // |im |i |ip==size() now mv i F->P, P-2
615  // data: x x x x(x x x x x x x)(x x x x x x x)
616  // |im |i |ip==size() now mv i F->P, P-2
617  // data: x x x x x x(x x x x x x)(x x x x x x)
618  // |im |i |ip==size() now mv i F->P, P-2
619  // data: x x x x x x x x(x x x x x)(x x x x x)
620  // |im |i |ip==size() now mv i F->P, P-2
621  // So, at each step, move i from F to P;
622  // if(P.N()<width+1) add 2 to F
623  // else if(ip==size()) sub 2 from P
624  // else add 1 to F, sub 1 from P
625  // NB when balanced, pts are add(sub)ed TWO at a time - does this affect result?
626  // --------------------------------------------------------------------------
627 
628  // clear the analysis vector
629  analvec.clear();
630 
631 // try to make index handling clean and neat
632 #define dvec(i) (data[i])
633 // use a dummy if xdata is not there
634 #define xvec(i) (noxdata ? T(i) : xdata[i])
635 // increment indexes - leave off last ;
636 #define inc(i) i++; if(!noflags) while(i<ilimit && flags[i]) i++
637 
638  // find the first good point, but don't necessarily increment
639  i = i0;
640  if (!noflags)
641  {
642  while (i < ilimit && flags[i])
643  {
644  i++;
645  }
646  }
647 
648  // TEMPtestTSS// keep deques containing the indexes i in the past and
649  // future stats TEMPtestTSS std::deque<int> pindex,findex;
650 
651  // start with two points in past, and up to width pts in future
652  // 'return -1' code above implies this will not overrun arrays
653  int iplus, iminus(i), isecond;
654  ptrPast->Add(xvec(i), dvec(i)); // put first point in past
655  // TEMPtestTSS pindex.push_back(i);
656  T xprev(xvec(i)), xmid; // save prev x for two-sample slips
657  inc(i); // second good point
658  ptrPast->Add(xvec(i), dvec(i)); // put second point in past
659  // TEMPtestTSS pindex.push_back(i);
660 
661  // fill the buffer
662  while (buff.size() < buffsize)
663  {
664  inc(i);
665  buff.push_back(i);
666  }
667 
668  // continue filling windows
669  if (fullwindows)
670  { // fill up past and future (x x...x)(x x...x)
671  while (ptrPast->N() < width)
672  { // assumes dsize > 2*width+buffsize
673  inc(i);
674  buff.push_back(i);
675  // always true here if(buff.size() > buffsize)
676  j = buff[0];
677  buff.pop_front();
678  ptrPast->Add(xvec(j), dvec(j));
679  // TEMPtestTSS pindex.push_back(j);
680  }
681  isecond = iplus = i;
682  while (ptrFuture->N() < width)
683  { // assumes dsize > 2*width+buffsize
684  // NB this fails: ptrFuture->Add(xvec(iplus),dvec(iplus++)); don't
685  // use it.
686  inc(iplus);
687  ptrFuture->Add(xvec(iplus), dvec(iplus));
688  // TEMPtestTSS findex.push_back(iplus);
689  }
690  inc(iplus);
691  }
692  else if (balanced)
693  { // start at (x x x)(x x x)
694  inc(i);
695  ptrPast->Add(xvec(i), dvec(i)); // put third point in past
696  // TEMPtestTSS pindex.push_back(i);
697  isecond = i;
698  xprev = xvec(i);
699  inc(i);
700  ptrFuture->Add(xvec(i), dvec(i)); // put 3 into future
701  // TEMPtestTSS findex.push_back(i);
702  inc(i);
703  ptrFuture->Add(xvec(i), dvec(i));
704  // TEMPtestTSS findex.push_back(i);
705  inc(i);
706  ptrFuture->Add(xvec(i), dvec(i));
707  // TEMPtestTSS findex.push_back(i);
708  inc(i);
709  iplus = i;
710  }
711  else
712  { // fill up the future (x x)(x x x ... x) x
713  isecond = iplus = i;
714  while (ptrFuture->N() < width)
715  { // assumes dsize > 2*width+buffsize
716  // NB this fails: ptrFuture->Add(xvec(iplus),dvec(iplus++)); don't
717  // use it.
718  inc(iplus);
719  ptrFuture->Add(xvec(iplus), dvec(iplus));
720  // TEMPtestTSS findex.push_back(iplus);
721  }
722  inc(iplus);
723  }
724 
725  // need the equivalent of i0+dsize-2
726  // or if(fullwindows) i0+dsize-width
727  int limm2(ilimit);
728  for (i = 0; i < 3; i++)
729  {
730  limm2--;
731  if (!noflags)
732  {
733  while (flags[limm2])
734  limm2--;
735  }
736  }
737 
738  // loop over all points
739  // NB no i++ in this for-loop (inc() instead), and no continues in loop
740  for (i = isecond; i < limm2;)
741  {
742  xprev = xvec(i);
743  inc(i); // instead of i++ in for(), do it here
744 
745  // save results in this, add to vector 'analvec'
746  Analysis A;
747  A.index = i;
748  A.pN = ptrPast->N();
749  A.fN = ptrFuture->N();
750  // assume slip happens at midpt of interval (this can matter with gaps)
751  xmid = xprev + 0.5 * (xvec(i) - xprev);
752  A.pave = ptrPast->Evaluate(xmid); // xvec(i));
753  A.fave = ptrFuture->Evaluate(xmid); // xvec(i));
754 
755  // Dump the TSS, build the TSS manually, and print that
756  // TEMPtestTSS {
757  // TEMPtestTSS gnsstk::TwoSampleStats<T> pTSS,fTSS;
758  // TEMPtestTSS unsigned int k;
759  // TEMPtestTSS std::string str;
760 
761  // TEMPtestTSS std::cout << "At i=" << i << " Past_indexes(" <<
762  // pindex.size() TEMPtestTSS << "):"; TEMPtestTSS for(k=0;
763  // k<pindex.size(); k++) { TEMPtestTSS std::cout << " " << pindex[k];
764  // TEMPtestTSS pTSS.Add(xvec(pindex[k]),dvec(pindex[k]));
765  // TEMPtestTSS }
766  // TEMPtestTSS std::cout << std::endl;
767 
768  // TEMPtestTSS str = pTSS.asString();
769  // TEMPtestTSS gnsstk::StringUtils::change(str,"\n"," ");
770  // TEMPtestTSS std::cout << std::fixed << std::setprecision(3) <<
771  // xvec(i) TEMPtestTSS << " pman " << str << std::endl;
772 
773  // TEMPtestTSS str = ptrPast->asString();
774  // TEMPtestTSS gnsstk::StringUtils::change(str,"\n"," ");
775  // TEMPtestTSS std::cout << std::fixed << std::setprecision(3) <<
776  // xvec(i) TEMPtestTSS << " past " << str << " eval " <<
777  // A.pave << std::endl;
778 
779  // TEMPtestTSS // ---------
780 
781  // TEMPtestTSS std::cout << "At i=" << i << " Futu_indexes(" <<
782  // findex.size() TEMPtestTSS << "):"; TEMPtestTSS for(k=0;
783  // k<findex.size(); k++) { TEMPtestTSS std::cout << " " << findex[k];
784  // TEMPtestTSS fTSS.Add(xvec(findex[k]),dvec(findex[k]));
785  // TEMPtestTSS }
786  // TEMPtestTSS std::cout << std::endl;
787 
788  // TEMPtestTSS str = fTSS.asString();
789  // TEMPtestTSS gnsstk::StringUtils::change(str,"\n"," ");
790  // TEMPtestTSS std::cout << std::fixed << std::setprecision(3) <<
791  // xvec(i) TEMPtestTSS << " fman " << str << std::endl;
792 
793  // TEMPtestTSS str = ptrFuture->asString();
794  // TEMPtestTSS gnsstk::StringUtils::change(str,"\n"," ");
795  // TEMPtestTSS std::cout << std::fixed << std::setprecision(3) <<
796  // xvec(i) TEMPtestTSS << " futu " << str << " eval " <<
797  // A.fave TEMPtestTSS << std::endl << std::endl;
798 
799  // TEMPtestTSS }
800 
801  // compute a "step" = difference in future and past averages
802  // must evaluate at the same x-point
803  // NB for two-sample, this accounts for slope - see Evaluate() in each
804  // filter
805  A.step = A.fave - A.pave;
806 
807  // get sigmas
808  // test variance - sometimes with large range in data, variance at
809  // small N < 0
810  A.psig = ptrPast->Variance();
811  A.fsig = ptrFuture->Variance();
812  if (A.psig <= T(0) && A.fsig <= T(0))
813  {
814  A.psig = A.fsig = T(1); // TD better?
815  }
816  else if (A.psig <= T(0))
817  {
818  A.psig = A.fsig = ::sqrt(A.fsig);
819  }
820  else if (A.fsig <= T(0))
821  {
822  A.psig = A.fsig = ::sqrt(A.psig);
823  }
824  else
825  {
826  A.psig = ::sqrt(A.psig);
827  A.fsig = ::sqrt(A.fsig);
828  }
829 
830  // compute a "sigma" = RSS of future and past stats
831  // TD add a sqrt(1/2) here? Technically the sum is
832  // sqrt(((Nf-1)*Varf+(Np-1)*Varp)/(Nf+Np-1))
833  // because "slip" is assumed removed, ave.s are same => above applies
834  // exactly
835  A.sigma =
836  ::sqrt((ptrFuture->Variance() + ptrPast->Variance()) / T(2.0));
837 
838  if (debug)
839  {
840  std::cout << "WF:FIL" << std::fixed << std::setprecision(osp) << " "
841  << std::setw(osw) << xvec(i) << " " << std::setw(osw)
842  << dvec(i) << " " << std::setw(osw) << A.step << " "
843  << std::setw(osw) << A.sigma << " " << std::setw(3)
844  << A.pN << " " << std::setw(osw) << A.pave << " "
845  << std::setw(osw) << A.psig << " " << std::setw(3) << A.fN
846  << " " << std::setw(osw) << A.fave << " "
847  << std::setw(osw) << A.fsig << " " << std::setw(osw)
848  << ::fabs(A.step / A.sigma) << std::endl;
849  }
850 
851  // save in analvec
852  analvec.push_back(A);
853 
854  // update stats ----------------------------------------------
855  // at each step, move i from F to P;
856  // if(P.N()<width+1) add 2 to F
857  // else if(ip==size()) sub 2 from P
858  // else add 1 to F, sub 1 from P
859  // move i from future to past
860  ptrFuture->Subtract(xvec(i), dvec(i));
861  // TEMPtestTSS findex.pop_front();
862  buff.push_back(i);
863  j = buff[0];
864  buff.pop_front();
865  ptrPast->Add(xvec(j), dvec(j));
866  // TEMPtestTSS pindex.push_back(j);
867 
868  // if fullwindows, quit when future meets limit
869  // ?? won't it just stop b/c loop reaches end?
870  // NB fullwindows overrides balanced
871  if (fullwindows && iplus >= i0 + dsize - 1)
872  {
873  break;
874  }
875 
876  // if balanced and future has met the end-of-data, remove two from past
877  if (balanced && iplus == i0 + dsize)
878  { // assumes data.size() > 2*width
879  // TEMPtestTSS std::cout << " balanced,fateod\n";
880  ptrPast->Subtract(xvec(iminus), dvec(iminus));
881  // TEMPtestTSS pindex.pop_front();
882  inc(iminus);
883  ptrPast->Subtract(xvec(iminus), dvec(iminus));
884  // TEMPtestTSS pindex.pop_front();
885  inc(iminus);
886  }
887 
888  // else if balanced and past not full, move two into the future
889  else if (balanced && ptrPast->N() < width + 1)
890  { // same assumption
891  // TEMPtestTSS std::cout << " balanced,pastnotfull\n";
892  ptrFuture->Add(xvec(iplus), dvec(iplus));
893  // TEMPtestTSS findex.push_back(iplus);
894  inc(iplus);
895  ptrFuture->Add(xvec(iplus), dvec(iplus));
896  // TEMPtestTSS findex.push_back(iplus);
897  inc(iplus);
898  }
899 
900  // else not near either end
901  else
902  {
903  // move iplus up by one
904  // TEMPtestTSS std::cout << " normal\n";
905  if (balanced || iplus < i0 + dsize - 1)
906  {
907  ptrFuture->Add(xvec(iplus), dvec(iplus));
908  // TEMPtestTSS findex.push_back(iplus);
909  inc(iplus);
910  }
911  // and move iminus up by one
912  if (balanced || ptrPast->N() > width)
913  {
914  ptrPast->Subtract(xvec(iminus), dvec(iminus));
915  // TEMPtestTSS pindex.pop_front();
916  inc(iminus);
917  }
918  }
919 
920  } // end loop over all data
921 
922  delete ptrPast;
923  delete ptrFuture;
924 
925 #undef xvec
926 #undef dvec
927 #undef inc
928 
929  return analvec.size();
930 
931  } // end WindowFilter::filter()
932 
933  //---------------------------------------------------------------------------------
934  // analysis, with debug print
935  // test 1a. ratio must be > minratio (2)
936  // test 1b. step must be > minstep (0.8)
937  // test 1c. step/minstep + ratio/minratio - 2 must be > minmargin (0.5)
938  // look in neighborhood of i - is ratio a local max and sigma a local min?
939  // test 2. ratio is a local max, n2=# intervals with right sign, n2 <=
940  // 2*halfwidth test 3. sigma is a local min, n3=# intervals with right sign,
941  // n3 <= 2*halfwidth test 4. fsig > psig before and psig > fsig after (count
942  // points that don't satisfy)
943  // allow one miss in count if |slip| is > 1
944  // return the number of FilterHit in results.
945  template <class T> int WindowFilter<T>::analyze()
946  {
947  // create first event = BOD; define npts later
948  results.clear();
949  {
950  FilterHit<T> fe;
951  fe.index = analvec[0].index;
952  fe.ngood = 0;
953  fe.type = FilterHit<T>::BOD;
954  results.push_back(fe);
955  }
956  int curr(0);
957  size_t i, j;
958  double tmp = 0.0;
959 
960  // ratio(step/sigma), its 1st diff, sigma, its 1st diff, future minus past
961  // sigma
962  std::deque<double> rat, rat1d, sig, sig1d, fminusp;
963  // messages added to analvec[i].msg;
964  std::string ratmsg, sigmsg, fmpmsg, wtmsg;
965  if (debug)
966  {
967  std::cout << "WF:ANL size is " << analvec.size() << std::endl;
968  }
969  for (i = 0; i < analvec.size(); i++)
970  { // loop over arrays
971 
972  // 'prime the pump' for the deques
973  if (i == 0)
974  {
975  for (j = 0; j < halfwidth; j++)
976  {
977  rat.push_back(0.0);
978  sig.push_back(0.0);
979  fminusp.push_back(0.0);
980  }
981  for (j = 0; (j <= halfwidth && j < analvec.size()); j++)
982  {
983  rat.push_back(
984  ::fabs(analvec[j].step / analvec[j].sigma)); // ratio
985  sig.push_back(analvec[j].sigma); // sigma
986  fminusp.push_back(analvec[j].fsig -
987  analvec[j].psig); // fsig - psig
988  }
989  for (j = 0; j < 2 * halfwidth; j++)
990  {
991  rat1d.push_back(0.0);
992  sig1d.push_back(0.0);
993  }
994  }
995 
996  // update the deques
997  else if (i + halfwidth < analvec.size())
998  {
999  // fill deques
1000  tmp = rat.back(); // ratio
1001  rat.push_back(::fabs(analvec[i + halfwidth].step /
1002  analvec[i + halfwidth].sigma));
1003  rat1d.push_back(rat.back() - tmp); // and its first diff
1004  tmp = sig.back(); // sigma
1005  sig.push_back(analvec[i + halfwidth].sigma);
1006  sig1d.push_back(sig.back() - tmp); // and sig first diff
1007  // fsig - psig .. no first diff
1008  fminusp.push_back(analvec[i + halfwidth].fsig -
1009  analvec[i + halfwidth].psig);
1010  }
1011 
1012  // keep deques size 2*half+1
1013  while (rat.size() > 2 * halfwidth + 1)
1014  {
1015  rat.pop_front();
1016  sig.pop_front();
1017  fminusp.pop_front();
1018  }
1019  // keep 1st difference deques size 2*half
1020  while (rat1d.size() > 2 * halfwidth)
1021  {
1022  rat1d.pop_front();
1023  sig1d.pop_front();
1024  }
1025 
1026  // test min/max in ratio, sig and fmp of the form +,+,+,any,-,-,-
1027  bool rmax = true, smin = true, fmp = true;
1028  int fmpcount(2 * halfwidth);
1029  double fmp0(fminusp[halfwidth]);
1030  double rat0(::fabs(rat[halfwidth]));
1031  for (j = 0; j < halfwidth; j++)
1032  {
1033  // test is that ratio is at maximum - so 1st dif is +,+,+,-,-,-
1034  // j= 0 1 2 h h+1 h+2
1035  if (j == halfwidth - 1)
1036  {
1037  if (rat1d[j] < 0.0)
1038  {
1039  rmax = false;
1040  }
1041  if (rat1d[j + halfwidth] > 0.0)
1042  {
1043  rmax = false;
1044  }
1045  }
1046  else
1047  {
1048  if (rat1d[j] < -rat0 / 10.0)
1049  {
1050  rmax = false;
1051  }
1052  if (rat1d[j + halfwidth] > rat0 / 10.0)
1053  {
1054  rmax = false;
1055  }
1056  }
1057 
1058  // if(rat1d[j] > 0.0) rmin=false; else
1059  // if(rat1d[j+halfwidth] < 0.0) rmin=false; else
1060 
1061  if (fminusp[j] - fmp0 < 0.0)
1062  {
1063  fmp = false;
1064  fmpcount--;
1065  }
1066  if (fminusp[j + halfwidth + 1] - fmp0 > 0.0)
1067  {
1068  fmp = false;
1069  fmpcount--;
1070  }
1071  }
1072 
1073  // if(twoSample) same as 1-samp when there's no gap, but with gap its
1074  // different
1075  // - see toy.gf.gap - looks like 2 limp clotheslines on big poles
1076  // +small,+verysmall,-big,(slim),+big,-verysmall,-small
1077  // sig1d[] 0 1 h-1 h h+1 h+2
1078  double slim(0.04 * analvec[i].sigma); // 5/16, was 0.02 // why 0.04?
1079  if (twoSample)
1080  {
1081  smin = true;
1082  if (-sig1d[halfwidth - 1] / slim < 2.0)
1083  {
1084  smin = false;
1085  }
1086  else if (sig1d[halfwidth] / slim < 2.0)
1087  {
1088  smin = false;
1089  }
1090  else
1091  {
1092  for (j = 0; j < halfwidth - 1; j++)
1093  {
1094  if (::fabs(sig1d[j] / sig1d[halfwidth - 1]) > 0.5)
1095  {
1096  smin = false;
1097  }
1098  if (::fabs(sig1d[halfwidth + 1 + j] / sig1d[halfwidth]) > 0.5)
1099  {
1100  smin = false;
1101  }
1102  }
1103  }
1104  }
1105  else
1106  {
1107  for (j = 0; j < halfwidth; j++)
1108  {
1109  // for 1-sample, test is sigma is at minimum - so 1st dif is
1110  // -,-,-,*,+,+,+
1111  if (sig1d[j] > slim)
1112  {
1113  smin = false;
1114  }
1115  if (sig1d[j + halfwidth] < -slim)
1116  {
1117  smin = false;
1118  }
1119  }
1120  }
1121 
1122  // make this configurable?
1123  if (2 * halfwidth - fmpcount <= halfwidth / 3)
1124  {
1125  fmp = true;
1126  }
1127 
1128  // define a weight [0,1], used in score but only if it passes first
1129  // tests
1130  double weight = (rmax ? 0.25 : 0) + (smin ? 0.25 : 0) +
1131  0.5 * fmpcount / double(2 * halfwidth);
1132 
1133  // dump all the deque to a string, for debug and dumpAnalMsg (verbose)
1134  // output
1135  {
1136  std::ostringstream oss;
1137  oss << " F-P" << std::fixed << std::setprecision(3);
1138  for (j = 0; j < fminusp.size(); j++)
1139  oss << "," << fminusp[j] - fmp0;
1140  oss << ",cnt=" << fmpcount << "/" << 2 * halfwidth;
1141  fmpmsg = oss.str();
1142  oss.str("");
1143  oss << " RAT1d" << std::fixed << std::setprecision(3);
1144  for (j = 0; j < rat1d.size(); j++)
1145  oss << "," << rat1d[j];
1146  ratmsg = oss.str();
1147  oss.str("");
1148  oss << " SIG1d" << std::scientific << std::setprecision(1);
1149  for (j = 0; j < sig1d.size(); j++)
1150  oss << "," << sig1d[j];
1151  oss << ",(" << slim << ")";
1152  sigmsg = oss.str();
1153  oss.str("");
1154  if (weight > 0)
1155  {
1156  if (tmp)
1157  {
1158  oss << " changeF-P " << std::scientific
1159  << std::setprecision(2) << tmp;
1160  }
1161  oss << " wt=" << std::fixed << std::setprecision(3) << weight;
1162  }
1163  wtmsg = oss.str();
1164  }
1165 
1166  // count it; only good data gets into analvec
1167  results[curr].ngood++;
1168 
1169  // debug print - also see single line below near end of routine
1170  if (debug)
1171  {
1172  std::cout << "WF:ANL"
1173  << " " << std::setw(3) << i << " " << std::setw(3)
1174  << analvec[i].index << std::fixed
1175  << std::setprecision(osp) << std::setw(osw) << " "
1176  << (noxdata ? T(analvec[i].index)
1177  : xdata[analvec[i].index])
1178  << " " << std::setw(osw) << data[analvec[i].index] << " "
1179  << std::setw(osw) << analvec[i].step << " "
1180  << std::setw(osw) << analvec[i].sigma << " "
1181  << std::setw(3) << analvec[i].pN << " " << std::setw(osw)
1182  << analvec[i].pave << " " << std::setw(osw)
1183  << analvec[i].psig << " " << std::setw(3) << analvec[i].fN
1184  << " " << std::setw(osw) << analvec[i].fave << " "
1185  << std::setw(osw) << analvec[i].fsig << " "
1186  << std::setw(osw)
1187  << ::fabs(analvec[i].step / analvec[i].sigma) << ratmsg
1188  << sigmsg << fmpmsg << wtmsg << std::flush;
1189  }
1190 
1191  // ---------------------- do the tests ----------------------
1192  // test 1a. ratio must be > minratio(2)
1193  if (::fabs(analvec[i].step / analvec[i].sigma) <= minratio)
1194  {
1195  if (debug)
1196  {
1197  std::cout << " small ratio" << std::flush;
1198  }
1199  analvec[i].score = -3; // failure
1200  analvec[i].msg = " small_ratio";
1201  }
1202 
1203  // test 1b. step must be > 0.8
1204  else if (::fabs(analvec[i].step) < minstep)
1205  {
1206  if (debug)
1207  {
1208  std::cout << " small step" << std::flush;
1209  }
1210  analvec[i].score = -2; // failure
1211  analvec[i].msg = " small_step";
1212  }
1213 
1214  // its too early - before we can compute score
1215  // usually ratio|step will be small, so not reach here
1216  else if (i == 0)
1217  {
1218  if (debug)
1219  {
1220  std::cout << " begin" << std::flush;
1221  }
1222  analvec[i].score = -1; // failure
1223  analvec[i].msg = " i=0_no_tests";
1224  }
1225 
1226  // approaching the end
1227  else if (i == analvec.size() - 1)
1228  {
1229  if (debug)
1230  {
1231  std::cout << " end" << std::flush;
1232  }
1233  analvec[i].score = -1; // failure
1234  analvec[i].msg = " i=end_no_tests";
1235  }
1236 
1237  // test 1c. exclude case where step AND ratio are very close to limit
1238  else if (::fabs(analvec[i].step / analvec[i].sigma) / minratio +
1239  ::fabs(analvec[i].step) / minstep - 2. <
1240  minmargin)
1241  {
1242  if (debug)
1243  {
1244  std::cout << " marginal" << std::flush;
1245  }
1246  analvec[i].score = -4; // failure
1247  analvec[i].msg = " marginal_step+ratio";
1248  }
1249 
1250  // test 2. ratio is a local max
1251  // test 3. sigma is a local min
1252  // test 4. fsig > psig before and psig > fsig after
1253  else if (!rmax || !smin || !fmp)
1254  { // maybe a slip
1255  std::string msg;
1256  if (!rmax)
1257  {
1258  msg = "; no-ratio-max";
1259  analvec[i].msg += msg + ratmsg;
1260  if (debug)
1261  {
1262  std::cout << msg;
1263  }
1264  }
1265  if (!smin)
1266  {
1267  msg = "; no-sig-min";
1268  analvec[i].msg += msg + sigmsg;
1269  if (debug)
1270  {
1271  std::cout << msg;
1272  }
1273  }
1274  if (!fmp)
1275  {
1276  msg = "; no-f-p";
1277  analvec[i].msg += msg + fmpmsg;
1278  if (debug)
1279  {
1280  std::cout << msg;
1281  }
1282  }
1283  analvec[i].score = int(100. * weight + 0.5);
1284  analvec[i].msg += wtmsg;
1285  if (debug)
1286  {
1287  std::cout << std::flush;
1288  }
1289  }
1290 
1291  else
1292  { // its a slip
1293  analvec[i].msg = ";" + ratmsg + ";" + sigmsg + ";" + fmpmsg + wtmsg;
1294  analvec[i].score = int(100. * weight + 0.5);
1295  results[curr].ngood--;
1296  results[curr].npts = analvec[i].index - results[curr].index;
1297  FilterHit<T> fe;
1298  fe.type = FilterHit<T>::slip;
1299  fe.index = analvec[i].index;
1300  fe.ngood = 1;
1301  fe.dx = 0.0;
1302  fe.step = analvec[i].step;
1303  fe.sigma = analvec[i].sigma;
1304  fe.score = analvec[i].score;
1305  fe.msg = analvec[i].msg;
1306  results.push_back(fe);
1307  curr++;
1308  }
1309 
1310  // if(!rmax || !smin || !fmp || analvec[i].score == -4) { // maybe a
1311  // slip
1312  // std::cout << " Maybe" << std::endl;
1313  // save the "almost slip" - TD add flag to turn this on
1314  // FilterNearMiss<T> fnm;
1315  // fnm.index = analvec[i].index;
1316  // fnm.step = analvec[i].step;
1317  // fnm.sigma = analvec[i].sigma;
1318  // fnm.score = analvec[i].score;
1319  // fnm.msg = analvec[i].msg;
1320  // maybes.push_back(fnm);
1321  //}
1322 
1323  // also see several lines above
1324  if (debug)
1325  {
1326  std::cout << " " << analvec[i].msg << std::endl;
1327  }
1328 
1329  } // end loop over analvec array
1330 
1331  // define npts for the last segment
1332  results[curr].npts =
1333  analvec[analvec.size() - 1].index - results[curr].index + 1;
1334 
1335  return (results.size());
1336 
1337  } // end WindowFilter::analyze()
1338 
1339  //---------------------------------------------------------------------------------
1340  template <class T>
1341  void WindowFilter<T>::dump(std::ostream& os, std::string tag)
1342  {
1343  size_t i, j, k;
1344  std::string msg(tag), slip, res;
1345 
1346  // TD print slope?
1347  os << "#" << msg << " WindowFilter::dump() with "
1348  << (twoSample ? "two" : "one") << "-sample stats, minStep "
1349  << std::fixed << std::setprecision(osp) << getMinStep() << " minRatio "
1350  << getMinRatio() << " width " << width << " btwn-buff " << buffsize
1351  << (noxdata ? " (xdata is index)" : "") << std::endl;
1352  os << "#"
1353  << msg
1354  //<< " i xdata data step sigma pN pave psig fN fave fsig ratio
1355  //slope ("
1356  << " i xdata data step sigma pN pave psig fN fave fsig ratio ("
1357  << (balanced ? "" : "not ") << "balanced, "
1358  << (twoSample ? "two" : "one") << "-sample stats)" << std::endl;
1359 
1360  // loop
1361  for (i = 0, j = 0, k = 0; i < data.size(); i++)
1362  {
1363  if (j >= analvec.size() || i != analvec[j].index)
1364  {
1365  if (dumpNA)
1366  {
1367  os << msg << std::fixed << std::setprecision(osp) << " "
1368  << std::setw(3) << i << " " << std::setw(osw)
1369  << (noxdata ? T(i) : xdata[i])
1370  //<< " " << std::setw(3) << (noflags ? 0 : flags[i])
1371  << " " << std::setw(osw) << data[i] << " " << std::setw(osw)
1372  << "--"
1373  << " " << std::setw(osw) << "--"
1374  << " " << std::setw(3) << 0 << " " << std::setw(osw) << "--"
1375  << " " << std::setw(osw) << "--"
1376  << " " << std::setw(3) << 0 << " " << std::setw(osw) << "--"
1377  << " " << std::setw(osw) << "--"
1378  << " " << std::setw(osw) << "--";
1379  if (dumpAmsg)
1380  {
1381  os << " no analysis";
1382  }
1383  os << std::endl;
1384  }
1385  }
1386  else
1387  {
1388  slip = res = "";
1389  if (analvec[j].score > 0)
1390  {
1391  if (analvec[j].score == 100)
1392  {
1393  slip = "";
1394  }
1395  else if (dumpAmsg)
1396  {
1397  slip = " maybe";
1398  }
1399  if (dumpAmsg)
1400  {
1401  std::stringstream ss;
1402  ss << " score:" << analvec[j].score;
1403  slip += ss.str();
1404  }
1405  }
1406 
1407  if (k < results.size() && i == results[k].index)
1408  {
1409  res = " " + (results[k].haveStats ? results[k].asStatsString(osp)
1410  : results[k].asString());
1411  k++;
1412  }
1413 
1414  os << msg << std::fixed << std::setprecision(osp) << " "
1415  << std::setw(3) << i << " " << std::setw(osw)
1416  << (noxdata ? T(i) : xdata[i])
1417  //<< " " << std::setw(3) << (noflags ? 0 : flags[i])
1418  << " " << std::setw(osw) << data[i] << " " << std::setw(osw)
1419  << analvec[j].step << " " << std::setw(osw) << analvec[j].sigma
1420  << " " << std::setw(3) << analvec[j].pN // past
1421  << " " << std::setw(osw) << analvec[j].pave << " "
1422  << std::setw(osw) << analvec[j].psig << " " << std::setw(3)
1423  << analvec[j].fN // future
1424  << " " << std::setw(osw) << analvec[j].fave << " "
1425  << std::setw(osw)
1426  << analvec[j].fsig
1427  // ratio:
1428  << " " << std::setw(osw)
1429  << ::fabs(analvec[j].step / analvec[j].sigma)
1430 
1431  // results(stats) string, slip string, analysis message
1432  << res << slip << (dumpAmsg ? analvec[j].msg : "") << std::endl;
1433  j++;
1434  }
1435  }
1436  } // end WindowFilter::dump()
1437 
1438  //---------------------------------------------------------------------------------
1439  // compute stats on the filter quanitites within the given FilterHit.
1440  // return the min, max, median and mad of sigma, the rss(future and past
1441  // stddev). if skip is true (default), exclude data within the filter width
1442  // of the end points, to avoid the bump(s) due to slip(s) at the FilterHit
1443  // boundaries.
1444  template <class T>
1446  {
1447  unsigned int i, j;
1448  sg.min = sg.max = sg.med = sg.mad = T(0);
1449  sg.haveStats = false;
1450 
1451  if (sg.type == FilterHit<T>::BOD)
1452  {
1453  return;
1454  }
1455 
1456  bool notfound(true);
1457  for (i = 0; i < analvec.size(); i++)
1458  {
1459  if (analvec[i].index == sg.index)
1460  {
1461  j = i;
1462  notfound = false;
1463  break;
1464  }
1465  }
1466  if (notfound)
1467  {
1468  return;
1469  }
1470 
1471  // stats on sigma // TD would like the same for step....how to
1472  // implement
1473  bool first(true);
1474  T sd;
1475  std::vector<T> sdv;
1476  for (i = 0; i < sg.ngood; i++)
1477  {
1478  if (skip)
1479  {
1480  if (i < width && sg.type != FilterHit<T>::outlier)
1481  {
1482  continue;
1483  }
1484  if (i > sg.npts - width)
1485  {
1486  continue;
1487  }
1488  }
1489  sd = analvec[j + i].sigma; // TD version for step?
1490  if (first)
1491  {
1492  sg.min = sg.max = sg.med = sd;
1493  first = false;
1494  }
1495  else
1496  {
1497  if (sd < sg.min)
1498  {
1499  sg.min = sd;
1500  }
1501  if (sd > sg.max)
1502  {
1503  sg.max = sd;
1504  }
1505  }
1506  sdv.push_back(sd);
1507  }
1508 
1509  i = sdv.size();
1510  if (i < 2)
1511  {
1512  return; // else MAD throws
1513  }
1514  sg.mad =
1515  gnsstk::Robust::MedianAbsoluteDeviation<T>(&sdv[0], i, sg.med, false);
1516  sg.haveStats = true;
1517  sdv.clear();
1518  }
1519 
1520  // end template <class T> class WindowFilter
1521 
1522 } // namespace gnsstk
1523 
1524 #endif // GNSSTK_WINDOWFILTER_HPP
gnsstk::WindowFilter::setWidth
void setWidth(int w)
Definition: WindowFilter.hpp:367
gnsstk::StatsFilterBase::Subtract
virtual void Subtract(const T &x, const T &y)=0
Subtract data from the statistics; in 1-sample stats the x is ignored.
gnsstk::StatsFilterBase::N
virtual unsigned int N() const =0
return the sample size
gnsstk::OneSampleStatsFilter::Slope
T Slope() const
Definition: WindowFilter.hpp:214
gnsstk::FilterHit::index
unsigned int index
index in the data array(s) at which this event occurs
Definition: StatsFilterHit.hpp:91
gnsstk::WindowFilter::isBalanced
bool isBalanced()
Definition: WindowFilter.hpp:376
gnsstk::WindowFilter::flags
const std::vector< int > & flags
reference to flags, parallel to data, 0 == good
Definition: WindowFilter.hpp:478
gnsstk::WindowFilter::isOneSample
bool isOneSample()
Definition: WindowFilter.hpp:375
gnsstk::WindowFilter::Analysis::pave
T pave
average of width points in past
Definition: WindowFilter.hpp:319
gnsstk::WindowFilter::setBufferSize
void setBufferSize(int b)
Definition: WindowFilter.hpp:368
gnsstk::TwoSampleStatsFilter::Average
T Average() const
return the average; in 2-sample stats this is AverageY()
Definition: WindowFilter.hpp:270
dvec
#define dvec(i)
gnsstk::WindowFilter::Analysis::psig
T psig
standard deviation of width points in past
Definition: WindowFilter.hpp:320
gnsstk::WindowFilter::getBufferSize
int getBufferSize()
Definition: WindowFilter.hpp:373
gnsstk::WindowFilter::getWidth
int getWidth()
Definition: WindowFilter.hpp:372
gnsstk::WindowFilter::data
const std::vector< T > & data
reference to data to be filtered
Definition: WindowFilter.hpp:476
gnsstk::FilterNearMiss::FilterNearMiss
FilterNearMiss()
empty and only constructor
Definition: WindowFilter.hpp:112
gnsstk::StatsFilterBase::StdDev
virtual T StdDev() const =0
return computed standard deviation, in 2-sample stats this is SigmaYX()
gnsstk::WindowFilter::dump
void dump(std::ostream &s, std::string tag=std::string())
Definition: WindowFilter.hpp:1341
gnsstk::StatsFilterBase::Intercept
virtual T Intercept() const =0
gnsstk::TwoSampleStatsFilter::asString
std::string asString() const
return the stats as a single string
Definition: WindowFilter.hpp:282
gnsstk::FilterNearMiss
Definition: WindowFilter.hpp:108
gnsstk::TwoSampleStatsFilter::Subtract
void Subtract(const T &x, const T &y)
Subtract data from the statistics.
Definition: WindowFilter.hpp:247
gnsstk::OneSampleStatsFilter::Evaluate
T Evaluate(T x) const
Definition: WindowFilter.hpp:208
gnsstk::StatsFilterBase::Evaluate
virtual T Evaluate(T x) const =0
return the predicted Y at the given X; in 1-sample stats this is Average()
gnsstk::OneSampleStatsFilter::Average
T Average() const
return the average
Definition: WindowFilter.hpp:202
gnsstk::WindowFilter::xdata
const std::vector< T > & xdata
reference to x-data to be filtered (TwoSample)
Definition: WindowFilter.hpp:475
gnsstk::WindowFilter::setw
void setw(int w)
Definition: WindowFilter.hpp:403
gnsstk::FilterHit::med
T med
Definition: StatsFilterHit.hpp:104
gnsstk::FilterHit::max
T max
Definition: StatsFilterHit.hpp:104
gnsstk::WindowFilter::Analysis::fN
unsigned int fN
number of points in the future buffer
Definition: WindowFilter.hpp:322
gnsstk::WindowFilter::Analysis::Analysis
Analysis()
constructor
Definition: WindowFilter.hpp:310
gnsstk::WindowFilter::getStats
void getStats(FilterHit< T > &fe, bool noedge=true)
Definition: WindowFilter.hpp:1445
gnsstk::WindowFilter::setDumpAnalMsg
void setDumpAnalMsg(bool b)
Definition: WindowFilter.hpp:394
gnsstk::WindowFilter::osw
int osw
Definition: WindowFilter.hpp:480
gnsstk::StatsFilterBase::Reset
virtual void Reset()=0
reset, i.e. ignore earlier data and restart sampling
gnsstk::WindowFilter::filter
int filter(const size_t index=0, int npts=-1)
Definition: WindowFilter.hpp:506
gnsstk::OneSampleStatsFilter::Variance
T Variance() const
return computed variance
Definition: WindowFilter.hpp:199
gnsstk::WindowFilter::reset
void reset()
Definition: WindowFilter.hpp:413
gnsstk::WindowFilter::Analysis::sigma
T sigma
combined standard deviation: RSS(stddev(f),stddev(p))
Definition: WindowFilter.hpp:316
gnsstk::WindowFilter::analvec
std::vector< Analysis > analvec
Definition: WindowFilter.hpp:489
gnsstk::TwoSampleStatsFilter::TwoSampleStatsFilter
TwoSampleStatsFilter()
constructor
Definition: WindowFilter.hpp:235
gnsstk::OneSampleStatsFilter::S
gnsstk::Stats< T > S
Definition: WindowFilter.hpp:226
gnsstk::WindowFilter::osp
int osp
width and precision for dump(), (default 8,3)
Definition: WindowFilter.hpp:480
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::Stats
Definition: Stats.hpp:137
gnsstk::TwoSampleStatsFilter
A StatsFilter class for two-sample statistics that inherits StatsFilterBase.
Definition: WindowFilter.hpp:231
gnsstk::WindowFilter::setBalanced
void setBalanced(bool b)
Definition: WindowFilter.hpp:370
Stats.hpp
gnsstk::FilterHit::score
unsigned int score
weight of slip (=100)
Definition: StatsFilterHit.hpp:96
gnsstk::TwoSampleStatsFilter::Variance
T Variance() const
return computed variance; in 2-sample stats this is VarianceYX()
Definition: WindowFilter.hpp:260
gnsstk::WindowFilter::setMinRatio
void setMinRatio(T val)
Definition: WindowFilter.hpp:379
gnsstk::WindowFilter::Analysis::fsig
T fsig
standard deviation of width points in future
Definition: WindowFilter.hpp:324
gnsstk::WindowFilter::setDumpNoAnal
void setDumpNoAnal(bool b)
in dump(), don't dump data when there was no analysis
Definition: WindowFilter.hpp:397
y
page HOWTO subpage DoxygenGuide Documenting Your Code page DoxygenGuide Documenting Your Code todo Flesh out this document section doctips Tips for Documenting When defining make sure that the prototype is identical between the cpp and hpp including both the namespaces and the parameter names for you have std::string as the return type in the hpp file and string as the return type in the cpp Doxygen may get confused and autolink to the cpp version with no documentation If you don t use the same parameter names between the cpp and hpp that will also confuse Doxygen Don t put type information in return or param documentation It doesn t really add anything and will often cause Doxygen to complain and not produce the documentation< br > use note Do not put a comma after a param name unless you mean to document multiple parameters< br/> the output stream</code >< br/> y
Definition: DOCUMENTING.dox:15
gnsstk::TwoSampleStatsFilter::Evaluate
T Evaluate(T x) const
return the predicted Y at the given X;
Definition: WindowFilter.hpp:273
gnsstk::WindowFilter::Analysis::fave
T fave
average of width points in future
Definition: WindowFilter.hpp:323
gnsstk::WindowFilter::dumpNA
bool dumpNA
if false, don't dump() data with no analysis (T)
Definition: WindowFilter.hpp:481
gnsstk::FilterNearMiss::index
int index
index in the data array(s) at which this event occurs
Definition: WindowFilter.hpp:114
gnsstk::WindowFilter::isFullWindows
bool isFullWindows()
Definition: WindowFilter.hpp:377
gnsstk::WindowFilter::Analysis::pN
unsigned int pN
number of points in the past buffer
Definition: WindowFilter.hpp:318
gnsstk::OneSampleStatsFilter::Reset
void Reset()
reset, i.e. ignore earlier data and restart sampling
Definition: WindowFilter.hpp:184
gnsstk::WindowFilter::getMinStep
T getMinStep()
Definition: WindowFilter.hpp:385
debug
#define debug
Definition: Rinex3ClockHeader.cpp:51
gnsstk::WindowFilter::willDumpNoAnal
bool willDumpNoAnal()
Definition: WindowFilter.hpp:398
gnsstk::StatsFilterBase::Add
virtual void Add(const T &x, const T &y)=0
Add data to the statistics; in 1-sample stats the x is ignored.
gnsstk::WindowFilter::setMinMargin
void setMinMargin(T val)
Definition: WindowFilter.hpp:381
gnsstk::WindowFilter
Definition: WindowFilter.hpp:302
gnsstk::WindowFilter::balanced
bool balanced
if true, 2 panes of sliding window have = size
Definition: WindowFilter.hpp:459
gnsstk::OneSampleStatsFilter
A StatsFilter class for one-sample statistics that inherits StatsFilterBase.
Definition: WindowFilter.hpp:177
gnsstk::StatsFilterBase::Variance
virtual T Variance() const =0
return computed variance, in 2-sample stats this is VarianceYX()
gnsstk::OneSampleStatsFilter::N
unsigned int N() const
return the sample size
Definition: WindowFilter.hpp:187
gnsstk::FilterHit::haveStats
bool haveStats
set true when getStats() is called
Definition: StatsFilterHit.hpp:102
gnsstk::StatsFilterBase::asString
virtual std::string asString() const =0
return the stats as a single string
gnsstk::FilterNearMiss::score
int score
weight of slip, 0 < score <= 100
Definition: WindowFilter.hpp:115
gnsstk::FilterHit::npts
unsigned int npts
number data points in segment (= a delta index)
Definition: StatsFilterHit.hpp:93
gnsstk::WindowFilter::Analysis::msg
std::string msg
readable description of what analysis found
Definition: WindowFilter.hpp:333
gnsstk::TwoSampleStatsFilter::Slope
T Slope() const
return the slope of the best-fit line Y=slope*X+intercept;
Definition: WindowFilter.hpp:276
gnsstk::WindowFilter::noxdata
bool noxdata
true when xdata array is not given
Definition: WindowFilter.hpp:464
gnsstk::WindowFilter::noflags
bool noflags
true when flags array is not given
Definition: WindowFilter.hpp:465
gnsstk::WindowFilter::halfwidth
unsigned int halfwidth
number of points on either side of slip analyzed
Definition: WindowFilter.hpp:468
gnsstk::WindowFilter::setprecision
void setprecision(int p)
Definition: WindowFilter.hpp:404
gnsstk::OneSampleStatsFilter::Add
void Add(const T &x, const T &y)
Add data to the statistics; in 1-sample stats the x is ignored.
Definition: WindowFilter.hpp:190
gnsstk::WindowFilter::Analysis::score
int score
Definition: WindowFilter.hpp:332
RobustStats.hpp
example3.data
data
Definition: example3.py:22
gnsstk::WindowFilter::dumpAmsg
bool dumpAmsg
if true, add analysis message in dump() (F)
Definition: WindowFilter.hpp:482
gnsstk::WindowFilter::setTwoSample
void setTwoSample(bool b)
Definition: WindowFilter.hpp:369
gnsstk::WindowFilter::Analysis::index
unsigned int index
index in original arrays to which this info applies.
Definition: WindowFilter.hpp:314
gnsstk::WindowFilter::getMinRatio
T getMinRatio()
Definition: WindowFilter.hpp:384
gnsstk::WindowFilter::Analysis::step
T step
step in average: average(future) - average(past)
Definition: WindowFilter.hpp:315
gnsstk::FilterHit::msg
std::string msg
message from analysis
Definition: StatsFilterHit.hpp:106
StatsFilterHit.hpp
gnsstk::TwoSampleStatsFilter::Add
void Add(const T &x, const T &y)
Add data to the statistics.
Definition: WindowFilter.hpp:244
gnsstk::TwoSampleStatsFilter::N
unsigned int N() const
return the sample size
Definition: WindowFilter.hpp:241
gnsstk::StatsFilterBase::Slope
virtual T Slope() const =0
gnsstk::TwoSampleStatsFilter::TSS
gnsstk::TwoSampleStats< T > TSS
Definition: WindowFilter.hpp:285
gnsstk::WindowFilter::setFullWindows
void setFullWindows(bool b)
Definition: WindowFilter.hpp:371
inc
#define inc(i)
gnsstk::FilterHit::ngood
unsigned int ngood
number of good (flag==0) points in this segment
Definition: StatsFilterHit.hpp:94
gnsstk::WindowFilter::getHalfWidth
int getHalfWidth()
Definition: WindowFilter.hpp:388
gnsstk::WindowFilter::isTwoSample
bool isTwoSample()
Definition: WindowFilter.hpp:374
gnsstk::WindowFilter::minstep
T minstep
|step|(=fut ave - past ave) < this is not slip
Definition: WindowFilter.hpp:470
gnsstk::WindowFilter::getDebug
bool getDebug()
Definition: WindowFilter.hpp:401
std
Definition: Angle.hpp:142
gnsstk::WindowFilter::Analysis
class used to store analysis arrays filled by the window filters.
Definition: WindowFilter.hpp:306
gnsstk::FilterHit::min
T min
Definition: StatsFilterHit.hpp:104
gnsstk::FilterNearMiss::sigma
T sigma
for a slip, RSS future and past sigma on the data
Definition: WindowFilter.hpp:117
gnsstk::WindowFilter::setPFFrac
void setPFFrac(T val)
Definition: WindowFilter.hpp:382
gnsstk::TwoSampleStatsFilter::StdDev
T StdDev() const
return computed standard deviation; in 2-sample stats this is SigmaYX()
Definition: WindowFilter.hpp:250
gnsstk::FilterHit::step
T step
for a slip, an estimate of the step in the data
Definition: StatsFilterHit.hpp:98
gnsstk::WindowFilter::fullwindows
bool fullwindows
if true, only process with full windows
Definition: WindowFilter.hpp:460
gnsstk::TwoSampleStatsFilter::Reset
void Reset()
reset, i.e. ignore earlier data and restart sampling
Definition: WindowFilter.hpp:238
gnsstk::FilterHit::type
event type
type of event: BOD, outlier(s), slip, other
Definition: StatsFilterHit.hpp:88
gnsstk::TwoSampleStatsFilter::Intercept
T Intercept() const
return the intercept of the best-fit line Y=slope*X+intercept;
Definition: WindowFilter.hpp:279
gnsstk::WindowFilter::WindowFilter
WindowFilter(const std::vector< T > &x, const std::vector< T > &d, const std::vector< int > &f)
Definition: WindowFilter.hpp:343
gnsstk::WindowFilter::pffrac
T pffrac
delta(f,p) sigma < this frac * sigma not a slip
Definition: WindowFilter.hpp:472
gnsstk::OneSampleStatsFilter::asString
std::string asString() const
return the stats as a single string
Definition: WindowFilter.hpp:223
gnsstk::WindowFilter::minmargin
T minmargin
limit on step/minstep+ratio/minratio-2
Definition: WindowFilter.hpp:471
gnsstk::OneSampleStatsFilter::Intercept
T Intercept() const
Definition: WindowFilter.hpp:220
gnsstk::WindowFilter::getResults
std::vector< FilterHit< T > > getResults()
get results vector of FilterHit
Definition: WindowFilter.hpp:407
gnsstk::WindowFilter::setMinStep
void setMinStep(T val)
Definition: WindowFilter.hpp:380
gnsstk::FilterHit::dx
T dx
step in xdata: before SLIP or after OUT
Definition: StatsFilterHit.hpp:100
gnsstk::FilterHit
Definition: StatsFilterHit.hpp:68
gnsstk::WindowFilter::twoSample
bool twoSample
if true, use two-sample statistics
Definition: WindowFilter.hpp:461
gnsstk::WindowFilter::setDebug
void setDebug(bool b)
debug prints in analysis()
Definition: WindowFilter.hpp:400
gnsstk::StatsFilterBase
Definition: WindowFilter.hpp:129
gnsstk::FilterHit::sigma
T sigma
for a slip, RSS future and past sigma on the data
Definition: StatsFilterHit.hpp:99
gnsstk::WindowFilter::debug
bool debug
if true, print debug messages in analyze() (F)
Definition: WindowFilter.hpp:483
gnsstk::WindowFilter::getPFFrac
T getPFFrac()
Definition: WindowFilter.hpp:387
gnsstk::WindowFilter::results
std::vector< FilterHit< T > > results
Definition: WindowFilter.hpp:496
gnsstk::WindowFilter::willDumpAnalMsg
bool willDumpAnalMsg()
Definition: WindowFilter.hpp:395
gnsstk::TwoSampleStats
Definition: Stats.hpp:126
gnsstk::WindowFilter::setHalfWidth
void setHalfWidth(int hw)
Definition: WindowFilter.hpp:383
xvec
#define xvec(i)
gnsstk::OneSampleStatsFilter::Subtract
void Subtract(const T &x, const T &y)
Subtract data from the statistics; in 1-sample stats the x is ignored.
Definition: WindowFilter.hpp:193
gnsstk::WindowFilter::buffsize
int buffsize
number of good points ignored btwn past, future
Definition: WindowFilter.hpp:463
gnsstk::StatsFilterBase::Average
virtual T Average() const =0
return the average; in 2-sample stats this is AverageY()
gnsstk::WindowFilter::minratio
T minratio
ratio=|step/sig| < this is not a slip
Definition: WindowFilter.hpp:469
gnsstk::OneSampleStatsFilter::StdDev
T StdDev() const
return computed standard deviation
Definition: WindowFilter.hpp:196
gnsstk::FilterNearMiss::msg
std::string msg
message from analyze()
Definition: WindowFilter.hpp:118
gnsstk::OneSampleStatsFilter::OneSampleStatsFilter
OneSampleStatsFilter()
constructor
Definition: WindowFilter.hpp:181
gnsstk::WindowFilter::width
unsigned int width
width or number of points in (1 pane of) window
Definition: WindowFilter.hpp:462
gnsstk::FilterHit::mad
T mad
robust stats on the filter quantities (not data)
Definition: StatsFilterHit.hpp:104
gnsstk::StatsFilterBase::StatsFilterBase
StatsFilterBase()
constructor
Definition: WindowFilter.hpp:133
gnsstk::WindowFilter::getMinMargin
T getMinMargin()
Definition: WindowFilter.hpp:386
gnsstk::FilterNearMiss::step
T step
an estimate of the step in the data
Definition: WindowFilter.hpp:116
gnsstk::WindowFilter::analyze
int analyze()
Definition: WindowFilter.hpp:945


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