SatPass.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 
40 
41 #ifndef GNSSTK_SATELLITE_PASS_INCLUDE
42 #define GNSSTK_SATELLITE_PASS_INCLUDE
43 
44 #include <map>
45 #include <ostream>
46 #include <string>
47 #include <vector>
48 
49 #include "gnsstk_export.h"
50 #include "Epoch.hpp"
51 #include "TimeString.hpp"
52 #include "Exception.hpp"
53 #include "GNSSconstants.hpp"
54 #include "RinexObsData.hpp"
55 #include "RinexObsHeader.hpp"
56 #include "RinexSatID.hpp"
57 #include "RinexUtilities.hpp"
58 
59 namespace gnsstk
60 {
61 
71  class SatPass
72  {
73  protected:
74  // --------------- SatPassData data structure for internal use only
81  struct SatPassData
82  {
83  // member data ----------------------------------
88  unsigned short flag;
89 
94  unsigned int userflag;
95 
97  unsigned int ndt;
98 
100  double toffset;
101 
103  std::vector<double> data;
104 
109  std::vector<unsigned short> lli, ssi;
110 
111  // private member functions ---------------------
112 
117  SatPassData(unsigned short n = 4)
118  : flag(SatPass::OK), userflag(0), ndt(0), toffset(0.0)
119  {
120  data = std::vector<double>(n, 0.0);
121  lli = std::vector<unsigned short>(n, 0);
122  ssi = std::vector<unsigned short>(n, 0);
123  }
124 
125  // d'tor, copy c'tor and operator= are built by compiler,
126  // but operator= will not work correctly, b/c a deep copy is needed.
128  {
129  if (&right != this)
130  {
131  flag = right.flag;
132  userflag = right.userflag;
133  ndt = right.ndt;
134  toffset = right.toffset;
135  data.resize(right.data.size());
136  lli.resize(right.lli.size());
137  ssi.resize(right.ssi.size());
138  int i;
139  for (i = 0; i < right.data.size(); i++)
140  data[i] = right.data[i];
141  for (i = 0; i < right.lli.size(); i++)
142  lli[i] = right.lli[i];
143  for (i = 0; i < right.ssi.size(); i++)
144  ssi[i] = right.ssi[i];
145  }
146 
147  return *this;
148  }
149  }; // end struct SatPassData
150 
151  // --------------- private member data -----------------------------
157  int Status;
158 
160  double dt;
161 
164 
169  std::map<std::string, unsigned int> indexForLabel;
170  std::map<unsigned int, std::string> labelForIndex;
171 
172  // above determined at construction; the rest determined by input data
173 
180 
182  unsigned int ngood;
183 
185  std::vector<SatPassData> spdvector;
186 
187  // --------------- private member functions ------------------------
188 
190  void init(const RinexSatID& sat, double dt,
191  std::vector<std::string> obstypes);
192 
200  int pushBack(const Epoch tt, SatPassData& spd);
201 
205  struct SatPassData getData(unsigned int i) const;
206 
207  public:
208  // ------------------ friends --------------------------------------
210  friend class gdc;
211 
216  friend class SatPassIterator;
217 
245  friend int SatPassFromRinexFiles(std::vector<std::string>& filenames,
246  std::vector<std::string>& obstypes,
247  double dt, std::vector<SatPass>& SPList,
248  std::vector<RinexSatID> exSats,
249  bool lenient, Epoch beginTime,
250  Epoch endTime);
251 
252  // ------------------ configuration --------------------------------
260  SatPass(const RinexSatID& sat, double dt);
261 
275  SatPass(const RinexSatID& sat, double dt,
276  std::vector<std::string> obstypes);
277 
280  SatPass& operator=(const SatPass& right);
281 
282  // Add data to the arrays at timetag tt; calls must be made in time order.
283  // Caller sets the flag to either BAD or OK later using flag().
284 
300  int addData(const Epoch& tt, std::vector<std::string>& obstypes,
301  std::vector<double>& data);
302 
318  int addData(const Epoch& tt, const std::vector<std::string>& obstypes,
319  const std::vector<double>& data,
320  const std::vector<unsigned short>& lli,
321  const std::vector<unsigned short>& ssi,
322  const unsigned short flag = SatPass::OK);
323 
336  int addData(const RinexObsData& robs);
337 
338  // -------------------------- get and set routines
339  // -------------------------- can change ssi, lli, data, but not
340  // times,sat,dt,ngood,count get and set flag so you can update ngood
341  // lvalue for the data or SSI/LLI arrays of this SatPass at index i
342 
344  int& status() { return Status; }
345 
347  int getStatus() const { return Status; }
348 
357  double& data(unsigned int i, const std::string& type);
358 
366  double& timeoffset(unsigned int i);
367 
376  unsigned short& LLI(unsigned int i, const std::string& type);
377 
386  unsigned short& SSI(unsigned int i, const std::string& type);
387 
388  // -------------------------------- set only
389  // --------------------------------
395  static double setMaxGap(double gap)
396  {
397  maxGap = gap;
398  return maxGap;
399  }
400 
406  void setOutputFormat(std::string fmt, int round = 3)
407  {
408  outFormat = fmt;
409  outRound = round;
410  }
411 
417  std::string getOutputFormat() { return outFormat; }
418 
425  void setFlag(unsigned int i, unsigned short flag);
426 
435  void setUserFlag(unsigned int i, unsigned int inflag);
436 
437  // -------------------------------- get only
438  // --------------------------------
443  double getMaxGap() const { return maxGap; }
444 
449  std::vector<std::string> getObsTypes()
450  {
451  std::vector<std::string> v;
452  for (int i = 0; i < labelForIndex.size(); i++)
453  v.push_back(labelForIndex[i]);
454  return v;
455  }
456 
463  unsigned short getFlag(unsigned int i) const;
464 
472  unsigned int getUserFlag(unsigned int i) const;
473 
478  Epoch getFirstTime() const;
479 
481  Epoch getLastTime() const;
482 
485  {
486  for (int j = 0; j < spdvector.size(); j++)
487  if (spdvector[j].flag & OK)
488  {
489  return time(j);
490  }
492  }
493 
496  {
497  for (int j = spdvector.size() - 1; j >= 0; j--)
498  if (spdvector[j].flag & OK)
499  {
500  return time(j);
501  }
503  }
504 
509  RinexSatID getSat() const { return sat; }
510 
515  double getDT() const { return dt; }
516 
521  int getNgood() const { return ngood; }
522 
527  unsigned int size() const { return spdvector.size(); }
528 
536  unsigned int getCount(unsigned int i) const;
537 
547  double data(unsigned int i, const std::string& type1, const std::string& type2) const;
548 
558  unsigned short LLI(unsigned int i, const std::string& type1, const std::string& type2);
559 
569  unsigned short SSI(unsigned int i, const std::string& type1, const std::string& type2);
570 
576  inline bool hasType(std::string type) const
577  {
578  return (indexForLabel.find(type) != indexForLabel.end());
579  }
580 
582  std::vector<std::string> getObstypes()
583  {
584  std::vector<std::string> ots;
585  for (int i = 0; i < labelForIndex.size(); i++)
586  ots.push_back(labelForIndex[i]);
587  return ots;
588  }
589 
590  // -------------------------------- utils
591  // ---------------------------------
593  void clear() { spdvector.clear(); }
594 
601  Epoch time(unsigned int i) const;
602 
610  int index(const Epoch& tt) const
611  {
612  int count = countForTime(tt);
613  if (count < 0)
614  {
615  return -1;
616  }
617  for (int i = 0; i < spdvector.size(); i++)
618  if (count == spdvector[i].ndt)
619  {
620  return i;
621  }
622  return -1;
623  }
624 
631  void renameObstypes(std::map<std::string, std::string>& subst)
632  {
633  unsigned int i;
634  std::map<std::string, std::string>::const_iterator it = subst.begin();
635  std::map<unsigned int, std::string>::iterator jt;
636  while (it != subst.end())
637  {
638  if (indexForLabel.find(it->first) == indexForLabel.end())
639  {
640  continue;
641  }
642 
643  i = indexForLabel[it->first];
644  indexForLabel.insert(
645  std::map<std::string, unsigned int>::value_type(it->second, i));
646  indexForLabel.erase(it->first);
647 
648  for (jt = labelForIndex.begin(); jt != labelForIndex.end(); ++jt)
649  {
650  if (jt->second != it->first)
651  {
652  continue;
653  }
654  i = jt->first;
655  labelForIndex.erase(i);
656  labelForIndex.insert(
657  std::map<unsigned int, std::string>::value_type(i,
658  it->second));
659  }
660 
661  ++it;
662  }
663  }
664 
665  // sorting ----------------------------------------------------------
667  bool operator<(const SatPass& right) const
668  {
669  if (firstTime == right.firstTime)
670  {
671  return (sat < right.sat);
672  }
673  return firstTime < right.firstTime;
674  }
675 
676  // edit -------------------------------------------------------------
683  bool includesTime(const Epoch& tt) const;
684 
692  int trimAfter(const Epoch ttag);
693 
699  bool split(int N, SatPass& newSP);
700 
713  void decimate(const int N, Epoch refTime = CommonTime::BEGINNING_OF_TIME);
714 
715  // compare ----------------------------------------------------------
722  bool hasOverlap(const SatPass& that, double *pdelt = NULL,
723  Epoch *pttb = NULL, Epoch *ptte = NULL);
724 
730  bool hasCommonView(const SatPass& that, double *pdelt = NULL,
731  Epoch *pttb = NULL, Epoch *ptte = NULL)
732  {
733  if (sat != that.sat)
734  {
735  return false;
736  }
737  return hasOverlap(that, pdelt, pttb, ptte);
738  }
739 
740  // analysis - also see SatPassUtilities -----------------------------
751  bool getGLOchannel(int& n, std::string& msg);
752 
781  void smooth(bool smoothPR, bool smoothPH, std::string& msg,
782  const double& wl1 = L1_WAVELENGTH_GPS,
783  const double& wl2 = L2_WAVELENGTH_GPS);
784 
808  void smoothSF(bool smoothPR, bool smoothPH, std::string& msg,
809  const int freq, double wl);
810 
811  // output -----------------------------------------------------------
818  std::string
819  toString(std::string msg = "",
820  std::string fmt =
821  "%04Y/%02m/%02d %02H:%02M:%06.3f = %04F %w %10.3g")
822  {
823  std::ostringstream os;
824  os << msg << " " << sat << " N " << std::setw(4) << size() << " good "
825  << std::setw(4) << ngood << " times "
826  << printTime(getFirstTime(), fmt) << " to "
827  << printTime(getLastTime(), fmt) << " obs:";
828  std::vector<std::string> ots = getObstypes();
829  for (int i = 0; i < ots.size(); i++)
830  os << " " << ots[i];
831  return os.str();
832  }
839  void dump(std::ostream& os, const std::string& msg1,
840  const std::string& msg2 = std::string());
841 
849  friend std::ostream& operator<<(std::ostream& os, SatPass& sp);
850 
851  // public member data -----------------------------------------------
853  GNSSTK_EXPORT
854  static const unsigned short BAD;
855 
861  GNSSTK_EXPORT
862  static const unsigned short OK;
863 
868  GNSSTK_EXPORT
869  static const unsigned short LL1;
870 
875  GNSSTK_EXPORT
876  static const unsigned short LL2;
877 
882  GNSSTK_EXPORT
883  static const unsigned short LL3;
884 
886  GNSSTK_EXPORT
887  static double maxGap;
888 
893  GNSSTK_EXPORT
894  static int outRound;
895  GNSSTK_EXPORT
896  static std::string outFormat;
897  GNSSTK_EXPORT
898  static std::string longfmt;
899 
900  protected:
906  int countForTime(const Epoch& tt) const
907  {
908  return int((tt - firstTime) / dt + 0.5);
909  }
910 
911  }; // end class SatPass
912 
919  std::ostream& operator<<(std::ostream& os, gnsstk::SatPass& sp);
920 
921 } // end namespace gnsstk
922 
923 // -----------------------------------------------------------------------------------
924 #endif // GNSSTK_SATELLITE_PASS_INCLUDE
gnsstk::SatPass::decimate
void decimate(const int N, Epoch refTime=CommonTime::BEGINNING_OF_TIME)
Definition: SatPass.cpp:1184
RinexUtilities.hpp
gnsstk::SatPass::labelForIndex
std::map< unsigned int, std::string > labelForIndex
Definition: SatPass.hpp:170
gnsstk::SatPass::index
int index(const Epoch &tt) const
Definition: SatPass.hpp:610
gnsstk::SatPass::clear
void clear()
clear the data (but not the obs types) from the arrays
Definition: SatPass.hpp:593
gnsstk::SatPass::getLastGoodTime
Epoch getLastGoodTime() const
Definition: SatPass.hpp:495
gnsstk::SatPass::addData
int addData(const Epoch &tt, std::vector< std::string > &obstypes, std::vector< double > &data)
Definition: SatPass.cpp:134
gnsstk::SatPass::SatPassData::ndt
unsigned int ndt
time 'count' : time of data = FirstTime + ndt * dt + offset
Definition: SatPass.hpp:97
gnsstk::SatPass::data
double & data(unsigned int i, const std::string &type)
Definition: SatPass.cpp:882
gnsstk::SatPass::maxGap
static GNSSTK_EXPORT double maxGap
size of maximum time gap, in seconds, allowed within SatPass data.
Definition: SatPass.hpp:887
gnsstk::SatPass::ngood
unsigned int ngood
number of timetags with good data in the data arrays.
Definition: SatPass.hpp:182
gnsstk::SatPass::indexForLabel
std::map< std::string, unsigned int > indexForLabel
Definition: SatPass.hpp:169
const
#define const
Definition: getopt.c:43
gnsstk::SatPass::operator<
bool operator<(const SatPass &right) const
'less than' is required for sort() and map<SatPass,...>.find(SatPass)
Definition: SatPass.hpp:667
gnsstk::SatPass::SatPassData::toffset
double toffset
offset of time from integer number * dt since FirstTime.
Definition: SatPass.hpp:100
gnsstk::SatPass::getFirstTime
Epoch getFirstTime() const
Definition: SatPass.cpp:1012
gnsstk::SatPass::countForTime
int countForTime(const Epoch &tt) const
Definition: SatPass.hpp:906
gnsstk::SatPass::toString
std::string toString(std::string msg="", std::string fmt="%04Y/%02m/%02d %02H:%02M:%06.3f = %04F %w %10.3g")
Definition: SatPass.hpp:819
gnsstk::SatPass::LL3
static const GNSSTK_EXPORT unsigned short LL3
Definition: SatPass.hpp:883
gnsstk::SatPass::BAD
static const GNSSTK_EXPORT unsigned short BAD
flag indicating bad data
Definition: SatPass.hpp:854
gnsstk::SatPass
Definition: SatPass.hpp:71
NULL
#define NULL
Definition: getopt1.c:64
gnsstk::SatPass::setOutputFormat
void setOutputFormat(std::string fmt, int round=3)
Definition: SatPass.hpp:406
gnsstk::CommonTime::BEGINNING_OF_TIME
static const GNSSTK_EXPORT CommonTime BEGINNING_OF_TIME
earliest representable CommonTime
Definition: CommonTime.hpp:102
gnsstk::SatPass::OK
static const GNSSTK_EXPORT unsigned short OK
Definition: SatPass.hpp:862
gnsstk::SatPass::getOutputFormat
std::string getOutputFormat()
Definition: SatPass.hpp:417
gnsstk::SatPass::operator=
SatPass & operator=(const SatPass &right)
Definition: SatPass.cpp:114
GNSSconstants.hpp
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::SatPass::dump
void dump(std::ostream &os, const std::string &msg1, const std::string &msg2=std::string())
Definition: SatPass.cpp:1343
gnsstk::SatPass::getMaxGap
double getMaxGap() const
Definition: SatPass.hpp:443
gnsstk::SatPass::SatPassData::flag
unsigned short flag
Definition: SatPass.hpp:88
gnsstk::SatPass::dt
double dt
Nominal time spacing of the data; determined on input or by decimate()
Definition: SatPass.hpp:160
gnsstk::L2_WAVELENGTH_GPS
const double L2_WAVELENGTH_GPS
GPS L2 carrier wavelength in meters.
Definition: DeprecatedConsts.hpp:59
gnsstk::SatPass::firstTime
Epoch firstTime
Definition: SatPass.hpp:179
gnsstk::SatPass::smooth
void smooth(bool smoothPR, bool smoothPH, std::string &msg, const double &wl1=L1_WAVELENGTH_GPS, const double &wl2=L2_WAVELENGTH_GPS)
Definition: SatPass.cpp:717
gnsstk::SatPass::pushBack
int pushBack(const Epoch tt, SatPassData &spd)
Definition: SatPass.cpp:1394
gnsstk::SatPass::LLI
unsigned short & LLI(unsigned int i, const std::string &type)
Definition: SatPass.cpp:908
gnsstk::CommonTime::END_OF_TIME
static const GNSSTK_EXPORT CommonTime END_OF_TIME
latest representable CommonTime
Definition: CommonTime.hpp:104
gnsstk::SatPass::getObsTypes
std::vector< std::string > getObsTypes()
Definition: SatPass.hpp:449
gnsstk::SatPass::SatPassData::operator=
SatPassData & operator=(const SatPassData &right)
Definition: SatPass.hpp:127
gnsstk::SatPass::getData
struct SatPassData getData(unsigned int i) const
Definition: SatPass.cpp:1433
gnsstk::SatPass::SatPassData::lli
std::vector< unsigned short > lli
Definition: SatPass.hpp:109
gnsstk::SatPass::getFirstGoodTime
Epoch getFirstGoodTime() const
Definition: SatPass.hpp:484
gnsstk::SatPass::smoothSF
void smoothSF(bool smoothPR, bool smoothPH, std::string &msg, const int freq, double wl)
Definition: SatPass.cpp:553
gnsstk::operator<<
std::ostream & operator<<(std::ostream &s, const ObsEpoch &oe) noexcept
Definition: ObsEpochMap.cpp:54
gnsstk::SatPass::getFlag
unsigned short getFlag(unsigned int i) const
Definition: SatPass.cpp:977
gnsstk::SatPass::getDT
double getDT() const
Definition: SatPass.hpp:515
gnsstk::SatPass::status
int & status()
Access the status; l-value may be assigned SP.status() = 1;.
Definition: SatPass.hpp:344
wl1
double wl1
Definition: DiscCorr.cpp:656
gnsstk::SatPass::outFormat
static GNSSTK_EXPORT std::string outFormat
Definition: SatPass.hpp:896
gnsstk::SatPass::setMaxGap
static double setMaxGap(double gap)
Definition: SatPass.hpp:395
gnsstk::SatPass::renameObstypes
void renameObstypes(std::map< std::string, std::string > &subst)
Definition: SatPass.hpp:631
gnsstk::SatPass::operator<<
friend std::ostream & operator<<(std::ostream &os, SatPass &sp)
Definition: SatPass.cpp:1378
gnsstk::SatPass::LL2
static const GNSSTK_EXPORT unsigned short LL2
Definition: SatPass.hpp:876
gnsstk::SatPass::getNgood
int getNgood() const
Definition: SatPass.hpp:521
gnsstk::SatPass::hasType
bool hasType(std::string type) const
Definition: SatPass.hpp:576
wl2
double wl2
Definition: DiscCorr.cpp:656
RinexObsData.hpp
gnsstk::SatPass::getGLOchannel
bool getGLOchannel(int &n, std::string &msg)
Definition: SatPass.cpp:309
gnsstk::SatPass::hasCommonView
bool hasCommonView(const SatPass &that, double *pdelt=NULL, Epoch *pttb=NULL, Epoch *ptte=NULL)
Definition: SatPass.hpp:730
gnsstk::SatPass::getUserFlag
unsigned int getUserFlag(unsigned int i) const
Definition: SatPass.cpp:990
gnsstk::SatPass::SatPassData::userflag
unsigned int userflag
Definition: SatPass.hpp:94
RinexObsHeader.hpp
example6.ssi
ssi
Definition: example6.py:124
gnsstk::SatPass::spdvector
std::vector< SatPassData > spdvector
ALL data in the pass, stored in SatPassData objects, in time order.
Definition: SatPass.hpp:185
gnsstk::SatPass::setUserFlag
void setUserFlag(unsigned int i, unsigned int inflag)
Definition: SatPass.cpp:964
gnsstk::printTime
std::string printTime(const CommonTime &t, const std::string &fmt)
Definition: TimeString.cpp:64
gnsstk::RinexSatID
Definition: RinexSatID.hpp:63
gnsstk::SatPass::lastTime
Epoch lastTime
Definition: SatPass.hpp:179
Exception.hpp
gnsstk::SatPass::timeoffset
double & timeoffset(unsigned int i)
Definition: SatPass.cpp:898
gnsstk::SatPass::trimAfter
int trimAfter(const Epoch ttag)
Definition: SatPass.cpp:249
gnsstk::SatPass::SatPassData::ssi
std::vector< unsigned short > ssi
Definition: SatPass.hpp:109
Epoch.hpp
gnsstk::gdc
Definition: gdc.hpp:319
gnsstk::SatPass::getLastTime
Epoch getLastTime() const
Definition: SatPass.cpp:1015
gnsstk::SatPass::longfmt
static GNSSTK_EXPORT std::string longfmt
Definition: SatPass.hpp:898
gnsstk::SatPass::SatPass
SatPass(const RinexSatID &sat, double dt)
Definition: SatPass.cpp:80
gnsstk::SatPass::LL1
static const GNSSTK_EXPORT unsigned short LL1
Definition: SatPass.hpp:869
gnsstk::SatPass::SatPassData::data
std::vector< double > data
data for one epoch of RINEX data
Definition: SatPass.hpp:103
gnsstk::SatPassIterator
Definition: SatPassIterator.hpp:55
gnsstk::SatPass::includesTime
bool includesTime(const Epoch &tt) const
Definition: SatPass.cpp:1110
gnsstk::Epoch
Definition: Epoch.hpp:123
gnsstk::SatPass::sat
RinexSatID sat
Satellite identifier for this data.
Definition: SatPass.hpp:163
gnsstk::SatPass::getObstypes
std::vector< std::string > getObstypes()
Access the obstypes (as strings)
Definition: SatPass.hpp:582
gnsstk::SatPass::split
bool split(int N, SatPass &newSP)
Definition: SatPass.cpp:1132
gnsstk::SatPass::time
Epoch time(unsigned int i) const
Definition: SatPass.cpp:1097
RinexSatID.hpp
gnsstk::SatPass::init
void init(const RinexSatID &sat, double dt, std::vector< std::string > obstypes)
called by constructors to initialize - see doc for them.
Definition: SatPass.cpp:97
gnsstk::SatPass::Status
int Status
Definition: SatPass.hpp:157
example6.lli
lli
Definition: example6.py:123
gnsstk::SatPass::SSI
unsigned short & SSI(unsigned int i, const std::string &type)
Definition: SatPass.cpp:924
gnsstk::L1_WAVELENGTH_GPS
const double L1_WAVELENGTH_GPS
GPS L1 carrier wavelength in meters.
Definition: DeprecatedConsts.hpp:57
gnsstk::RinexObsData
Definition: RinexObsData.hpp:68
gnsstk::SatPass::getSat
RinexSatID getSat() const
Definition: SatPass.hpp:509
gnsstk::SatPass::setFlag
void setFlag(unsigned int i, unsigned short flag)
Definition: SatPass.cpp:942
gnsstk::SatPass::getStatus
int getStatus() const
Access the status as r-value only.
Definition: SatPass.hpp:347
gnsstk::SatPass::hasOverlap
bool hasOverlap(const SatPass &that, double *pdelt=NULL, Epoch *pttb=NULL, Epoch *ptte=NULL)
Definition: SatPass.cpp:1259
gnsstk::SatPass::size
unsigned int size() const
Definition: SatPass.hpp:527
gnsstk::SatPass::SatPassFromRinexFiles
friend int SatPassFromRinexFiles(std::vector< std::string > &filenames, std::vector< std::string > &obstypes, double dt, std::vector< SatPass > &SPList, std::vector< RinexSatID > exSats, bool lenient, Epoch beginTime, Epoch endTime)
gnsstk::SatPass::outRound
static GNSSTK_EXPORT int outRound
Definition: SatPass.hpp:894
gnsstk::SatPass::SatPassData
Definition: SatPass.hpp:81
gnsstk::SatPass::SatPassData::SatPassData
SatPassData(unsigned short n=4)
Definition: SatPass.hpp:117
TimeString.hpp
gnsstk::SatPass::getCount
unsigned int getCount(unsigned int i) const
Definition: SatPass.cpp:1001
sp
double sp
Definition: IERS1996NutationData.hpp:46


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