Classes | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Friends | List of all members
gnsstk::SatPass Class Reference

Detailed Description

class SatPass holds all range and phase data for a full satellite pass. Constructed and filled by the calling program, it is used to pass data into and out of the GNSSTK discontinuity corrector. NB. if objects of this class are combined together, e.g. in STL containers such as list or vector, they MUST be consistently defined, namely the number of observation types must be the same, otherwise a nasty segmentation fault can occur when building the STL container.

Definition at line 71 of file SatPass.hpp.

#include <SatPass.hpp>

Inheritance diagram for gnsstk::SatPass:
Inheritance graph
[legend]

Classes

struct  SatPassData
 

Public Member Functions

int addData (const Epoch &tt, const std::vector< std::string > &obstypes, const std::vector< double > &data, const std::vector< unsigned short > &lli, const std::vector< unsigned short > &ssi, const unsigned short flag=SatPass::OK)
 
int addData (const Epoch &tt, std::vector< std::string > &obstypes, std::vector< double > &data)
 
int addData (const RinexObsData &robs)
 
void clear ()
 clear the data (but not the obs types) from the arrays More...
 
double & data (unsigned int i, const std::string &type)
 
double data (unsigned int i, const std::string &type1, const std::string &type2) const
 
void decimate (const int N, Epoch refTime=CommonTime::BEGINNING_OF_TIME)
 
void dump (std::ostream &os, const std::string &msg1, const std::string &msg2=std::string())
 
unsigned int getCount (unsigned int i) const
 
double getDT () const
 
Epoch getFirstGoodTime () const
 
Epoch getFirstTime () const
 
unsigned short getFlag (unsigned int i) const
 
bool getGLOchannel (int &n, std::string &msg)
 
Epoch getLastGoodTime () const
 
Epoch getLastTime () const
 
double getMaxGap () const
 
int getNgood () const
 
std::vector< std::string > getObsTypes ()
 
std::vector< std::string > getObstypes ()
 Access the obstypes (as strings) More...
 
std::string getOutputFormat ()
 
RinexSatID getSat () const
 
int getStatus () const
 Access the status as r-value only. More...
 
unsigned int getUserFlag (unsigned int i) const
 
bool hasCommonView (const SatPass &that, double *pdelt=NULL, Epoch *pttb=NULL, Epoch *ptte=NULL)
 
bool hasOverlap (const SatPass &that, double *pdelt=NULL, Epoch *pttb=NULL, Epoch *ptte=NULL)
 
bool hasType (std::string type) const
 
bool includesTime (const Epoch &tt) const
 
int index (const Epoch &tt) const
 
unsigned short & LLI (unsigned int i, const std::string &type)
 
unsigned short LLI (unsigned int i, const std::string &type1, const std::string &type2)
 
bool operator< (const SatPass &right) const
 'less than' is required for sort() and map<SatPass,...>.find(SatPass) More...
 
SatPassoperator= (const SatPass &right)
 
void renameObstypes (std::map< std::string, std::string > &subst)
 
 SatPass (const RinexSatID &sat, double dt)
 
 SatPass (const RinexSatID &sat, double dt, std::vector< std::string > obstypes)
 
void setFlag (unsigned int i, unsigned short flag)
 
void setOutputFormat (std::string fmt, int round=3)
 
void setUserFlag (unsigned int i, unsigned int inflag)
 
unsigned int size () const
 
void smooth (bool smoothPR, bool smoothPH, std::string &msg, const double &wl1=L1_WAVELENGTH_GPS, const double &wl2=L2_WAVELENGTH_GPS)
 
void smoothSF (bool smoothPR, bool smoothPH, std::string &msg, const int freq, double wl)
 
bool split (int N, SatPass &newSP)
 
unsigned short & SSI (unsigned int i, const std::string &type)
 
unsigned short SSI (unsigned int i, const std::string &type1, const std::string &type2)
 
int & status ()
 Access the status; l-value may be assigned SP.status() = 1;. More...
 
Epoch time (unsigned int i) const
 
double & timeoffset (unsigned int i)
 
std::string toString (std::string msg="", std::string fmt="%04Y/%02m/%02d %02H:%02M:%06.3f = %04F %w %10.3g")
 
int trimAfter (const Epoch ttag)
 

Static Public Member Functions

static double setMaxGap (double gap)
 

Static Public Attributes

static const GNSSTK_EXPORT unsigned short BAD = 0
 flag indicating bad data More...
 
static const GNSSTK_EXPORT unsigned short LL1 = 2
 
static const GNSSTK_EXPORT unsigned short LL2 = 4
 
static const GNSSTK_EXPORT unsigned short LL3 = 6
 
static GNSSTK_EXPORT std::string longfmt
 
static GNSSTK_EXPORT double maxGap = 1800
 size of maximum time gap, in seconds, allowed within SatPass data. More...
 
static const GNSSTK_EXPORT unsigned short OK = 1
 
static GNSSTK_EXPORT std::string outFormat
 
static GNSSTK_EXPORT int outRound = 3
 

Protected Member Functions

int countForTime (const Epoch &tt) const
 
struct SatPassData getData (unsigned int i) const
 
void init (const RinexSatID &sat, double dt, std::vector< std::string > obstypes)
 called by constructors to initialize - see doc for them. More...
 
int pushBack (const Epoch tt, SatPassData &spd)
 

Protected Attributes

double dt
 Nominal time spacing of the data; determined on input or by decimate() More...
 
Epoch firstTime
 
std::map< std::string, unsigned int > indexForLabel
 
std::map< unsigned int, std::string > labelForIndex
 
Epoch lastTime
 
unsigned int ngood
 number of timetags with good data in the data arrays. More...
 
RinexSatID sat
 Satellite identifier for this data. More...
 
std::vector< SatPassDataspdvector
 ALL data in the pass, stored in SatPassData objects, in time order. More...
 
int Status
 

Friends

class gdc
 class gdc is used to detect and correct cycleslips More...
 
std::ostream & operator<< (std::ostream &os, SatPass &sp)
 
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)
 
class SatPassIterator
 

Constructor & Destructor Documentation

◆ SatPass() [1/2]

gnsstk::SatPass::SatPass ( const RinexSatID sat,
double  dt 
)

Constructor for the given sat; default obs types are L1, L2, P1, P2, in that order; dt is the nominal time spacing of the data. NB. dt MUST be correct.

Parameters
satthe satellite from which this data comes
dtthe nominal time spacing (seconds) of the data

Definition at line 80 of file SatPass.cpp.

◆ SatPass() [2/2]

gnsstk::SatPass::SatPass ( const RinexSatID sat,
double  dt,
std::vector< std::string >  obstypes 
)

Constructor from a list of strings <=> RINEX obs types to be read NB. The number of obstypes determines the size of the SatPass object; therefore objects with different numbers of obs types must not be combined together in things like STL containers, which assume a fixed size for all objects of one class. NB. dt MUST be correct.

Parameters
satthe satellite from which this data comes
dtthe nominal time spacing (seconds) of the data
obstypesa vector of strings, each string being a 2-character RINEX observation type, e.g. "L1", "P2", to be stored.

Definition at line 91 of file SatPass.cpp.

Member Function Documentation

◆ addData() [1/3]

int gnsstk::SatPass::addData ( const Epoch tt,
const std::vector< std::string > &  obstypes,
const std::vector< double > &  data,
const std::vector< unsigned short > &  lli,
const std::vector< unsigned short > &  ssi,
const unsigned short  flag = SatPass::OK 
)

Add vector of data, identified by obstypes (same as used in c'tor) at tt, Flag, lli and ssi are set using input (parallel to data).

Parameters
ttthe time tag of interest
obstypesa vector of strings, each string being a 2-character RINEX observation type, e.g. "L1", "P2", to be stored. This MUST match the list used in the constructor.
dataa vector of data values, parallel to the obstypes vector
llia vector of LLI values, parallel to the obstypes vector
ssia vector of SSI values, parallel to the obstypes vector
Returns
n>=0 if data was added successfully, n is the index of the new data -1 if a gap is found (no data is added), -2 if time tag is out of order (no data is added)
Exceptions
Exception

Definition at line 151 of file SatPass.cpp.

◆ addData() [2/3]

int gnsstk::SatPass::addData ( const Epoch tt,
std::vector< std::string > &  obstypes,
std::vector< double > &  data 
)

Add vector of data, identified by obstypes (same as used in c'tor) at tt, Flag is set 'good' and lli=ssi=0

Parameters
ttthe time tag of interest
obstypesa vector of strings, each string being a 2-character RINEX observation type, e.g. "L1", "P2", to be stored. This MUST match the list used in the constructor.
dataa vector of data values, parallel to the obstypes vector
Returns
n>=0 if data was added successfully, n is the index of the new data -1 if a gap is found (no data is added), -2 if time tag is out of order (no data is added)
Exceptions
Exception

Definition at line 134 of file SatPass.cpp.

◆ addData() [3/3]

int gnsstk::SatPass::addData ( const RinexObsData robs)

Add data as found in RinexObsData. No action if this->sat is not found. Pull out time tag and all data in obs type list. All flags are set 'good'.

Parameters
robsRinex observation data from which to pull data. Only data for the object's satellite is added.
Returns
n>=0 if data was added successfully, n is the index of the new data -1 if a gap is found (no data is added), -2 if time tag is out of order (no data is added) -3 if the satellite was not found in the RinexObsData (no data added)

Definition at line 197 of file SatPass.cpp.

◆ clear()

void gnsstk::SatPass::clear ( )
inline

clear the data (but not the obs types) from the arrays

Definition at line 593 of file SatPass.hpp.

◆ countForTime()

int gnsstk::SatPass::countForTime ( const Epoch tt) const
inlineprotected

compute the count associated with the time tt

Parameters
ttthe time tag of interest
Exceptions
Exception

Definition at line 906 of file SatPass.hpp.

◆ data() [1/2]

double & gnsstk::SatPass::data ( unsigned int  i,
const std::string &  type 
)

Access the data for one obs type at one index, as either l-value or r-value

Parameters
iindex of the data of interest
typeobservation type (e.g. "L1") of the data of interest
Returns
the data of the given type at the given index
Exceptions
Exception

Definition at line 882 of file SatPass.cpp.

◆ data() [2/2]

double gnsstk::SatPass::data ( unsigned int  i,
const std::string &  type1,
const std::string &  type2 
) const

Access the data for either of two obs type at one index, as r-value only

Parameters
iindex of the data of interest
type1observation type (e.g. "P1") of the data of interest
type2observation type (e.g. "C1") of the data of interest
Returns
the data of the given type at the given index
Exceptions
Exception

Definition at line 1022 of file SatPass.cpp.

◆ decimate()

void gnsstk::SatPass::decimate ( const int  N,
Epoch  refTime = CommonTime::BEGINNING_OF_TIME 
)

Decimate the data in the SatPass by (integer) factor N, referencing refTime; that is keep only epochs that satisfy time=refTime+n*N*dt where n is also an integer, and dt is the current time spacing of the time spacing of the SatPass. This routine decimates the data, reduces the arrays, and may change the start and stop times and ngood; time offsets are not changed.

Parameters
NNew time spacing is N(>1) times the current time spacing
refTimeReference Epoch for the decimation, default is to use first in pass
Exceptions
Exception

Definition at line 1184 of file SatPass.cpp.

◆ dump()

void gnsstk::SatPass::dump ( std::ostream &  os,
const std::string &  msg1,
const std::string &  msg2 = std::string() 
)

Dump all the data in the pass, one line per timetag.

Parameters
osoutput stream
msg1put message msg1 at beginning of each line,
msg2put msg2 at the end of the first (#comment) line.

Definition at line 1343 of file SatPass.cpp.

◆ getCount()

unsigned int gnsstk::SatPass::getCount ( unsigned int  i) const

get one element of the count array of this SatPass

Parameters
iindex of the data of interest
Returns
the count at the given index. Count is the number of timesteps DT between the first time tag and the current time tag.
Exceptions
Exception

Definition at line 1001 of file SatPass.cpp.

◆ getData()

struct SatPass::SatPassData gnsstk::SatPass::getData ( unsigned int  i) const
protected

get a complete SatPassData at count i

Exceptions
Exception

Definition at line 1433 of file SatPass.cpp.

◆ getDT()

double gnsstk::SatPass::getDT ( ) const
inline

get the time interval of this SatPass

Returns
the nominal time step (seconds) in this data

Definition at line 515 of file SatPass.hpp.

◆ getFirstGoodTime()

Epoch gnsstk::SatPass::getFirstGoodTime ( ) const
inline
Returns
the earliest time of good data in this SatPass data

Definition at line 484 of file SatPass.hpp.

◆ getFirstTime()

Epoch gnsstk::SatPass::getFirstTime ( ) const
Returns
the earliest time (full, including toffset) in this SatPass data

Definition at line 1012 of file SatPass.cpp.

◆ getFlag()

unsigned short gnsstk::SatPass::getFlag ( unsigned int  i) const

get the flag at one index

Parameters
iindex of the data of interest
Returns
the flag for the given index
Exceptions
Exception

Definition at line 977 of file SatPass.cpp.

◆ getGLOchannel()

bool gnsstk::SatPass::getGLOchannel ( int &  n,
std::string &  msg 
)

compute the GLO channel start at n, then set n before returning; return false if failure challenge is at low elevation, L1 is slightly better than L2, but need both return true if successful, false if failed; also return string msg, which is FINAL sat n wk sow(beg) wk sow(end) npt stddev slope sl/std stddev(slope) [??] NB if "??" appears at end of msg, results questionable (stddev(slope) is high)

Exceptions
Exception

Definition at line 309 of file SatPass.cpp.

◆ getLastGoodTime()

Epoch gnsstk::SatPass::getLastGoodTime ( ) const
inline
Returns
the latest time of good data in this SatPass data

Definition at line 495 of file SatPass.hpp.

◆ getLastTime()

Epoch gnsstk::SatPass::getLastTime ( ) const
Returns
the latest time (full, including toffset) in this SatPass data

Definition at line 1015 of file SatPass.cpp.

◆ getMaxGap()

double gnsstk::SatPass::getMaxGap ( ) const
inline

get the max. gap limit size (seconds); for all SatPass objects

Returns
the current value of maximum gap (sec)

Definition at line 443 of file SatPass.hpp.

◆ getNgood()

int gnsstk::SatPass::getNgood ( ) const
inline

get the number of good points in this SatPass

Returns
the number of good points (flag != BAD) in this object

Definition at line 521 of file SatPass.hpp.

◆ getObsTypes()

std::vector<std::string> gnsstk::SatPass::getObsTypes ( )
inline

get the list of obstypes

Returns
the vector of strings giving RINEX obs types

Definition at line 449 of file SatPass.hpp.

◆ getObstypes()

std::vector<std::string> gnsstk::SatPass::getObstypes ( )
inline

Access the obstypes (as strings)

Definition at line 582 of file SatPass.hpp.

◆ getOutputFormat()

std::string gnsstk::SatPass::getOutputFormat ( )
inline

get the timetag output format

Returns
The format of time tags in the output (cf. gnsstk Epoch::printTime() for syntax)

Definition at line 417 of file SatPass.hpp.

◆ getSat()

RinexSatID gnsstk::SatPass::getSat ( ) const
inline

get the satellite of this SatPass

Returns
the satellite of this SatPass data

Definition at line 509 of file SatPass.hpp.

◆ getStatus()

int gnsstk::SatPass::getStatus ( ) const
inline

Access the status as r-value only.

Definition at line 347 of file SatPass.hpp.

◆ getUserFlag()

unsigned int gnsstk::SatPass::getUserFlag ( unsigned int  i) const

get the userflag at one index NB SatPass does nothing w/ this member except setUserFlag() and getUserFlag();

Parameters
iindex of the data of interest
Exceptions
Exception

Definition at line 990 of file SatPass.cpp.

◆ hasCommonView()

bool gnsstk::SatPass::hasCommonView ( const SatPass that,
double *  pdelt = NULL,
Epoch pttb = NULL,
Epoch ptte = NULL 
)
inline

Determine if there is common-view between this SatPass and another, that is if the satellites match and the time limits overlap. Return the time in seconds of the overlap.

Definition at line 730 of file SatPass.hpp.

◆ hasOverlap()

bool gnsstk::SatPass::hasOverlap ( const SatPass that,
double *  pdelt = NULL,
Epoch pttb = NULL,
Epoch ptte = NULL 
)

Determine if there is overlap between data in this SatPass and another, that is the time limits overlap. If pointers are defined, return: pdelt: the time in seconds of the overlap, pttb: begin time of the overlap ptte: end time of the overlap

Definition at line 1259 of file SatPass.cpp.

◆ hasType()

bool gnsstk::SatPass::hasType ( std::string  type) const
inline

Test whether the object has obstype type

Returns
true if this obstype was passed to the c'tor (i.e. is in indexForLabel)

Definition at line 576 of file SatPass.hpp.

◆ includesTime()

bool gnsstk::SatPass::includesTime ( const Epoch tt) const

return true if the given timetag is or could be part of this pass

Parameters
ttthe time tag of interest
Returns
true if the given time tag lies within the time interval covered by this object.

Definition at line 1110 of file SatPass.cpp.

◆ index()

int gnsstk::SatPass::index ( const Epoch tt) const
inline

compute the index to which the input time tt is closest;

Parameters
ttthe time tag of interest
Returns
-1 if not within the time limits of the SatPass, else index of tt
Exceptions
Exception

Definition at line 610 of file SatPass.hpp.

◆ init()

void gnsstk::SatPass::init ( const RinexSatID sat,
double  dt,
std::vector< std::string >  obstypes 
)
protected

called by constructors to initialize - see doc for them.

Definition at line 97 of file SatPass.cpp.

◆ LLI() [1/2]

unsigned short & gnsstk::SatPass::LLI ( unsigned int  i,
const std::string &  type 
)

Access the LLI for one obs type at one index, as either l-value or r-value

Parameters
iindex of the data of interest
typeobservation type (e.g. "L1") of the data of interest
Returns
the LLI of the given type at the given index
Exceptions
Exception

Definition at line 908 of file SatPass.cpp.

◆ LLI() [2/2]

unsigned short gnsstk::SatPass::LLI ( unsigned int  i,
const std::string &  type1,
const std::string &  type2 
)

Access the LLI for either of two obs type at one index, as r-value only

Parameters
iindex of the data of interest
type1observation type (e.g. "P1") of the data of interest
type2observation type (e.g. "C1") of the data of interest
Returns
the LLI of the given type at the given index
Exceptions
Exception

Definition at line 1046 of file SatPass.cpp.

◆ operator<()

bool gnsstk::SatPass::operator< ( const SatPass right) const
inline

'less than' is required for sort() and map<SatPass,...>.find(SatPass)

Definition at line 667 of file SatPass.hpp.

◆ operator=()

SatPass & gnsstk::SatPass::operator= ( const SatPass right)

d'tor, copy c'tor are built by compiler; so is operator= but don't use it!

Definition at line 114 of file SatPass.cpp.

◆ pushBack()

int gnsstk::SatPass::pushBack ( const Epoch  tt,
SatPassData spd 
)
protected

add a complete SatPassData at time tt

Returns
n>=0 if data was added successfully, n is the index of the new data -1 if a gap is found (no data is added), -2 if time tag is out of order (no data is added)

Definition at line 1394 of file SatPass.cpp.

◆ renameObstypes()

void gnsstk::SatPass::renameObstypes ( std::map< std::string, std::string > &  subst)
inline

substitute obstype labels - used e.g. to ignore C1/P1 differences Replace all instances of OT with subs[OT], if subst[OT] exists. the input map must NOT have circularities: e.g. <C1,P1>, <P1,Q1>

Exceptions
Exception

Definition at line 631 of file SatPass.hpp.

◆ setFlag()

void gnsstk::SatPass::setFlag ( unsigned int  i,
unsigned short  flag 
)

set the flag at one index to flag - use the SatPass constants OK, etc.

Parameters
iindex of the data of interest
flagflag (e.g. SatPass::BAD).
Exceptions
Exception

Definition at line 942 of file SatPass.cpp.

◆ setMaxGap()

static double gnsstk::SatPass::setMaxGap ( double  gap)
inlinestatic

change the maximum time gap (in seconds) allowed within any SatPass

Parameters
gapThe maximum time gap (in seconds) allowed within any SatPass
Returns
the input value.

Definition at line 395 of file SatPass.hpp.

◆ setOutputFormat()

void gnsstk::SatPass::setOutputFormat ( std::string  fmt,
int  round = 3 
)
inline

set timetag output format

Parameters
fmtThe format of time tags in the output (cf. gnsstk Epoch::printTime() for syntax)

Definition at line 406 of file SatPass.hpp.

◆ setUserFlag()

void gnsstk::SatPass::setUserFlag ( unsigned int  i,
unsigned int  inflag 
)

set the userflag at one index to inflag; NB SatPass does nothing w/ this member except setUserFlag() and getUserFlag();

Parameters
iindex of the data of interest
inflagunsigned int flag meaning whatever the user wants
Exceptions
Exception

Definition at line 964 of file SatPass.cpp.

◆ size()

unsigned int gnsstk::SatPass::size ( ) const
inline

get the size of (the arrays in) this SatPass

Returns
the size of the data array in this object

Definition at line 527 of file SatPass.hpp.

◆ smooth()

void gnsstk::SatPass::smooth ( bool  smoothPR,
bool  smoothPH,
std::string &  msg,
const double &  wl1 = L1_WAVELENGTH_GPS,
const double &  wl2 = L2_WAVELENGTH_GPS 
)

Smooth pseudorange and debias phase, by computing the best estimate of the range-minus-phase over the whole pass, and subtracting this bias from the raw phase. NB. remove an INTEGER (cycles) to get "debiased phase" but a REAL (m) to get "smoothed pseudorange"; thus smoothed pseudorange != debiased phase. This routine can be called ONLY if dual frequency range and phase data (C/P1,C/P2,L1,L2) have been stored, and should be called ONLY after ALL cycleslips have been removed.

Parameters
smoothPRif true, replace the pseudorange (P1 and P2) with smoothed ranges (= phase + REAL estimate of range-minus-phase in m).
smoothPHif true, replace the phase (L1 and L2) with debiased phase (= phase + INTEGER estimate of range-minus-phase in cycles).
msga string containing a single-line statistical summary of the smoothing results, and the estimated phase biases.
wl1wavelength of L1 for this data
wl2wavelength of L2 for this data This string consists of the following 18 fields separated by whitespace. 1) "SMT", 2) satellite id (e.g. G07), 3) start GPS week, 4) start GPS seconds of week, 5) end GPS week, 6) end GPS seconds of week, (7-11 are for the L1 bias data in units of meters) 7) number, 8) average, 9) std deviation, 10) minimum, and 11) maximum, (12-16 are for the L2 bias data in units of meters) 12) number, 13) average, 14) std deviation, 15) minimum, and 16) maximum, 17) the L1 bias in cycles, 18) the L2 bias in cycles.
Exceptions
Exception

Definition at line 717 of file SatPass.cpp.

◆ smoothSF()

void gnsstk::SatPass::smoothSF ( bool  smoothPR,
bool  smoothPH,
std::string &  msg,
const int  freq,
double  wl 
)

Single frequency version of smooth(); cf. smooth(). This includes a crude cycleslip detector (15m bias change).

Parameters
smoothPRif true, replace the pseudorange with smoothed range (= phase + REAL estimate of range-minus-phase in m).
smoothPHif true, replace the phase with debiased phase (= phase + INTEGER estimate of range-minus-phase in cycles).
msga string containing a single-line statistical summary of the smoothing results, and the estimated phase biases.
freqinteger 1 or 2, as data to smooth is L1,C1/P1 or L2,C2/P2.
wlwavelength of phase for this data This string consists of the following 18 fields separated by whitespace. 1) "SMT", 2) satellite id (e.g. G07), 3) start GPS week, 4) start GPS seconds of week, 5) end GPS week, 6) end GPS seconds of week, (7-11 are for the L1 bias data in units of meters) 7) number, 8) average, 9) std deviation, 10) minimum, and 11) maximum, (12-16 are for the L2 bias data in units of meters) 12) number, 13) average, 14) std deviation, 15) minimum, and 16) maximum, 17) the L1 bias in cycles, 18) the L2 bias in cycles.
Exceptions
Exception

Definition at line 553 of file SatPass.cpp.

◆ split()

bool gnsstk::SatPass::split ( int  N,
SatPass newSP 
)

create a new SatPass from the given one, starting at count N. modify this SatPass to end just before N. return true if successful.

Definition at line 1132 of file SatPass.cpp.

◆ SSI() [1/2]

unsigned short & gnsstk::SatPass::SSI ( unsigned int  i,
const std::string &  type 
)

Access the ssi for one obs type at one index, as either l-value or r-value

Parameters
iindex of the data of interest
typeobservation type (e.g. "L1") of the data of interest
Returns
the SSI of the given type at the given index
Exceptions
Exception

Definition at line 924 of file SatPass.cpp.

◆ SSI() [2/2]

unsigned short gnsstk::SatPass::SSI ( unsigned int  i,
const std::string &  type1,
const std::string &  type2 
)

Access the ssi for either of two obs type at one index, as r-value only

Parameters
iindex of the data of interest
type1observation type (e.g. "P2") of the data of interest
type2observation type (e.g. "C2") of the data of interest
Returns
the SSI of the given type at the given index
Exceptions
Exception

Definition at line 1070 of file SatPass.cpp.

◆ status()

int& gnsstk::SatPass::status ( )
inline

Access the status; l-value may be assigned SP.status() = 1;.

Definition at line 344 of file SatPass.hpp.

◆ time()

Epoch gnsstk::SatPass::time ( unsigned int  i) const

compute the timetag associated with index i in the data array

Parameters
iindex of the data of interest
Returns
the time tag at the given index.
Exceptions
Exception

Definition at line 1097 of file SatPass.cpp.

◆ timeoffset()

double & gnsstk::SatPass::timeoffset ( unsigned int  i)

Access the time offset from the nominal time (i.e. timetag) at one index (epoch), as either l-value or r-value

Parameters
iindex of the data of interest
Returns
the time offset from nominal at the given index
Exceptions
Exception

Definition at line 898 of file SatPass.cpp.

◆ toString()

std::string gnsstk::SatPass::toString ( std::string  msg = "",
std::string  fmt = "%04Y/%02m/%02d %02H:%02M:%06.3f = %04F %w %10.3g" 
)
inline

Dump one line summary of the pass; do not put linefeed at end

Parameters
msgput message msg1 at beginning of line
fmtuse time format
Returns
string containing summary, without LF at end.

Definition at line 819 of file SatPass.hpp.

◆ trimAfter()

int gnsstk::SatPass::trimAfter ( const Epoch  ttag)

Truncate all data at and after the given time. return -1 if ttag is at or before the start of this pass, return +1 if ttag is at or after the end of this pass, else return 0

Exceptions
Exception

Definition at line 249 of file SatPass.cpp.

Friends And Related Function Documentation

◆ gdc

friend class gdc
friend

class gdc is used to detect and correct cycleslips

Definition at line 210 of file SatPass.hpp.

◆ operator<<

std::ostream& operator<< ( std::ostream &  os,
SatPass sp 
)
friend

Write a one-line summary of the object, consisting of total points, satellite, number of good points, status, start time, end time, time step (sec), and observation types.

Parameters
osoutput stream
spSatPass object to output

Stream output for SatPass.

Parameters
osoutput stream to write to
spSatPass to write
Returns
reference to os.

Definition at line 1378 of file SatPass.cpp.

◆ SatPassFromRinexFiles

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 
)
friend

Read a set of RINEX observation files, filling a vector of SatPass objects. Create the SatPass objects using the input list of observation types and timestep. If there are no obs types given (vector obstypes has size 0), then use the obs types in the header of the first file read. The files are sorted on their begin time before processing, and the resulting list of SatPass objects is in time order. Data before the begin time, and after the end time, is ignored. The list of SatPass objects need not be empty on input; however if not empty, then the list must be consistent with the input timestep and obs type list, and it will be sorted to be in time order. If a file cannot be opened, or it is not RINEX observation, simply skip it.

Parameters
filenamesvector of input RINEX observation file names
obstypesvector of observation types to include in SatPass (may be empty: include all)
dtdata interval of existing SPList and input files
SPListvector of SatPass objects to fill, need not be empty, but if not empty, must have consistent obs types and dt.
lenientif true (default), be lenient in reading the RINEX format
beginTimereject data before this time (BEGINNING_OF_TIME)
endTimereject data after this time (END_OF TIME)
Returns
-1 if the filenames list is empty, otherwise return the number of files successfully read (may be less than the number input).
Exceptions
gnsstk::Exceptionif there are exceptions while reading, if the data in the file is out of time order.
Deprecated:
in favor of RinexObsFilesLoader version

Read a set of RINEX observation files, filling a vector of SatPass objects. Create the SatPass objects using the input list of observation types and timestep. If there are no obs types given (vector obstypes has size 0), then use the obs types in the header of the first file read. The files are sorted on their begin time before processing, and the resulting list of SatPass objects is in time order. Data before the begin time, and after the end time, is ignored. The list of SatPass objects need not be empty on input; however if not empty, then the list must be consistent with the input timestep and obs type list, and it will be sorted to be in time order. If a file cannot be opened, or it is not RINEX observation, simply skip it. NB. ngood for this SPL reflects # epochs with ALL obstypes != 0

Parameters
filenamesvector of input RINEX observation file names
obstypesvector of observation types to include in SatPass (may be empty: include all)
dtdata interval of existing SPList and input files
SPListvector of SatPass objects to fill, need not be empty, but if not empty, must have consistent obs types and dt.
exSatsvector of satellites to exclude
lenientif true (default), be lenient in reading the RINEX format
beginTimereject data before this time (BEGINNING_OF_TIME)
endTimereject data after this time (END_OF TIME)
Returns
-1 if the filenames list is empty, otherwise return the number of files successfully read (may be less than the number input).
Exceptions
gnsstk::Exceptionif there are exceptions while reading, if the data in the file is out of time order.

◆ SatPassIterator

friend class SatPassIterator
friend

class SatPassIterator allows the caller to access all the data in a list of SatPass objects in time order.

Definition at line 216 of file SatPass.hpp.

Member Data Documentation

◆ BAD

const unsigned short gnsstk::SatPass::BAD = 0
static

flag indicating bad data

Definition at line 854 of file SatPass.hpp.

◆ dt

double gnsstk::SatPass::dt
protected

Nominal time spacing of the data; determined on input or by decimate()

Definition at line 160 of file SatPass.hpp.

◆ firstTime

Epoch gnsstk::SatPass::firstTime
protected

nominally, timetags of the first and last data points; in fact firstTime is used with toffset to give the full time, so these are actually times - toffset

Definition at line 179 of file SatPass.hpp.

◆ indexForLabel

std::map<std::string, unsigned int> gnsstk::SatPass::indexForLabel
protected

STL map relating strings identifying obs types with indexes in SatPassData. E.g. index = indexForLabel[label].

Definition at line 169 of file SatPass.hpp.

◆ labelForIndex

std::map<unsigned int, std::string> gnsstk::SatPass::labelForIndex
protected

Definition at line 170 of file SatPass.hpp.

◆ lastTime

Epoch gnsstk::SatPass::lastTime
protected

Definition at line 179 of file SatPass.hpp.

◆ LL1

const unsigned short gnsstk::SatPass::LL1 = 2
static

flag indicating good data with phase discontinuity on L1 only. if(flag & LL1) then there is an L1 discontinuity

Definition at line 869 of file SatPass.hpp.

◆ LL2

const unsigned short gnsstk::SatPass::LL2 = 4
static

flag indicating good data with phase discontinuity on L2 only. if(flag & LL2) then there is an L2 discontinuity

Definition at line 876 of file SatPass.hpp.

◆ LL3

const unsigned short gnsstk::SatPass::LL3 = 6
static

flag indicating good data with phase discontinuity on both L1 and L2. if(flag & LL3) then there are L1 and L2 discontinuities

Definition at line 883 of file SatPass.hpp.

◆ longfmt

string gnsstk::SatPass::longfmt
static
Initial value:
=
string("%04Y/%02m/%02d %02H:%02M:%06.3f = %04F %10.3g")

Definition at line 898 of file SatPass.hpp.

◆ maxGap

double gnsstk::SatPass::maxGap = 1800
static

size of maximum time gap, in seconds, allowed within SatPass data.

Definition at line 887 of file SatPass.hpp.

◆ ngood

unsigned int gnsstk::SatPass::ngood
protected

number of timetags with good data in the data arrays.

Definition at line 182 of file SatPass.hpp.

◆ OK

const unsigned short gnsstk::SatPass::OK = 1
static

flag indicating good data with no phase discontinuity NB test for 'good' data using (flag != SatPass::BAD), NOT (flag == SatPass::OK).

Definition at line 862 of file SatPass.hpp.

◆ outFormat

string gnsstk::SatPass::outFormat
static
Initial value:
=
string("%4F %10.3g")

Definition at line 896 of file SatPass.hpp.

◆ outRound

int gnsstk::SatPass::outRound = 3
static

format string, as defined in class Epoch, for output of times used by smooth (debug), dump and operator<<

Definition at line 894 of file SatPass.hpp.

◆ sat

RinexSatID gnsstk::SatPass::sat
protected

Satellite identifier for this data.

Definition at line 163 of file SatPass.hpp.

◆ spdvector

std::vector<SatPassData> gnsstk::SatPass::spdvector
protected

ALL data in the pass, stored in SatPassData objects, in time order.

Definition at line 185 of file SatPass.hpp.

◆ Status

int gnsstk::SatPass::Status
protected

Status flag for use exclusively by the caller. It is set to 0 by the constructors, but otherwise ignored by class SatPass and class SatPassIterator.

Definition at line 157 of file SatPass.hpp.


The documentation for this class was generated from the following files:


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