This class models the header for a RINEX 3 Observation File.
RINEX 2 is also supported.
Definition at line 155 of file Rinex3ObsHeader.hpp.
#include <Rinex3ObsHeader.hpp>
Classes | |
class | ExtraWaveFact |
RINEX 2 extra "WAVELENGTH FACT" lines. More... | |
class | Fields |
class | Rinex3CorrInfo |
Public Types | |
typedef std::vector< Rinex3CorrInfo > | CorrVec |
Corrections (e.g. code bias) vector. More... | |
typedef std::map< std::string, std::string > | DisAmbMap |
Map SysChar + R2 Obs Type to Obs ID. More... | |
typedef std::vector< ExtraWaveFact > | FactorVector |
Vector of wavelength factors. More... | |
enum | Field { validInvalid = 0, validVersion, validFirst = validVersion, validRunBy, validComment, validMarkerName, validMarkerNumber, validMarkerType, validObserver, validReceiver, validAntennaType, validAntennaPosition, validAntennaDeltaHEN, validAntennaDeltaXYZ, validAntennaPhaseCtr, validAntennaBsightXYZ, validAntennaZeroDirAzi, validAntennaZeroDirXYZ, validCenterOfMass, validNumObs, validSystemNumObs, validWaveFact, validSigStrengthUnit, validInterval, validFirstTime, validLastTime, validReceiverOffset, validSystemDCBSapplied, validSystemPCVSapplied, validSystemScaleFac, validSystemPhaseShift, validGlonassSlotFreqNo, validGlonassCodPhsBias, validLeapSeconds, validNumSats, validPrnObs, validLast } |
typedef std::set< Field > | FieldSet |
typedef std::map< RinexObsID, double > | GLOCodPhsBias |
Map GLONASS SV observable to code phase bias. More... | |
typedef std::map< RinexSatID, int > | GLOFreqNumMap |
Map GLONASS SV ID to frequency number. More... | |
typedef std::vector< int > | IntVec |
Simple vector of ints. More... | |
typedef std::map< std::string, RinexObsID > | ObsIDMap |
typedef std::map< RinexObsID, SVPhsShftMap > | ObsPhsShftMap |
Map observation type to sv-phase shift map. More... | |
typedef std::map< RinexSatID, IntVec > | PRNNumObsMap |
Type used to count the number of observations for each observable. More... | |
typedef std::map< std::string, RinexObsVec > | RinexObsMap |
typedef std::vector< RinexObsID > | RinexObsVec |
Vector of obervables. More... | |
typedef std::map< RinexObsID, int > | ScaleFacMap |
typedef std::vector< std::string > | StringVec |
Commonly used vector of strings. More... | |
typedef std::map< RinexSatID, double > | SVPhsShftMap |
Map satellite ID to phase shift. More... | |
typedef std::map< std::string, ObsPhsShftMap > | SysPhsShftMap |
Map system to observation type phase shift map. More... | |
typedef std::map< std::string, ScaleFacMap > | SysScaleFacMap |
typedef std::map< std::string, ObsIDMap > | VersionObsMap |
Public Member Functions | |
void | clear () |
bool | compare (const Rinex3ObsHeader &right, StringVec &diffs, const StringVec &inclExclList, bool incl=false) |
virtual void | dump (std::ostream &s) const |
void | dump (std::ostream &s, double dumpVersion) const |
virtual std::size_t | getObsIndex (const std::string &sys, const RinexObsID &obsID) const |
virtual std::size_t | getObsIndex (const std::string &type) const |
short | getWavelengthFactor1 () |
short | getWavelengthFactor2 () |
virtual bool | isHeader () const |
bool | isValid () const |
Return boolean : is this a valid Rinex header? More... | |
int | numberHeaderRecordsToBeWritten (void) const noexcept |
void | parseHeaderRecord (std::string &line) |
void | prepareVer2Write (void) |
Rinex3ObsHeader () | |
A Simple Constructor. More... | |
Rinex3ObsHeader & | setWavelengthFactor (short wf1, short wf2) |
Setter method for convenience of python bindings. More... | |
void | writeHeaderRecords (FFStream &s) const |
virtual | ~Rinex3ObsHeader () |
Destructor. More... | |
![]() | |
virtual | ~Rinex3ObsBase () |
Destructor. More... | |
![]() | |
void | getRecord (FFStream &s) |
virtual bool | isData () const |
void | putRecord (FFStream &s) const |
virtual | ~FFData (void) |
virtual desctuctor More... | |
Static Public Member Functions | |
static Field | asField (const std::string &s) |
Convert a RINEX header field label string into its matching enum. More... | |
static std::string | asString (Field b) |
Return the RINEX header label for the given field enumeration. More... | |
Public Attributes | |
std::string | agency |
observer's agency More... | |
gnsstk::Triple | antennaBsightXYZ |
ANTENNA B.SIGHT XYZ. More... | |
gnsstk::Triple | antennaDeltaHEN |
ANTENNA: DELTA H/E/N. More... | |
gnsstk::Triple | antennaDeltaXYZ |
ANTENNA: DELTA X/Y/Z. More... | |
std::string | antennaObsCode |
ANTENNA P.CTR BLOCK: OBS CODE. More... | |
gnsstk::Triple | antennaPhaseCtr |
ANTENNA P.CTR BLOCK: PCTR POS. More... | |
gnsstk::Triple | antennaPosition |
APPROX POSITION XYZ. More... | |
std::string | antennaSatSys |
ANTENNA P.CTR BLOCK: SAT SYS. More... | |
double | antennaZeroDirAzi |
ANTENNA ZERODIR AZI. More... | |
gnsstk::Triple | antennaZeroDirXYZ |
ANTENNA ZERODIR XYZ. More... | |
std::string | antNo |
antenna number More... | |
std::string | antType |
antenna type More... | |
gnsstk::Triple | centerOfMass |
vehicle CENTER OF MASS: XYZ More... | |
StringVec | commentList |
comments in header More... | |
std::string | date |
when program was run More... | |
FactorVector | extraWaveFactList |
WAVELENGTH FACT (per SV) More... | |
std::string | fileAgency |
who ran program More... | |
std::string | fileProgram |
program used to generate file More... | |
std::string | fileSys |
file sys char: RinexSatID system OR Mixed More... | |
SatID | fileSysSat |
fileSys as a SatID More... | |
std::string | fileType |
CivilTime | firstObs |
TIME OF FIRST OBS. More... | |
GLOCodPhsBias | glonassCodPhsBias |
GLONASS COD/PHS/BIS. More... | |
GLOFreqNumMap | glonassFreqNo |
GLONASS SLOT / FRQ #. More... | |
CorrVec | infoDCBS |
DCBS INFO. More... | |
CorrVec | infoPCVS |
PCVS INFO. More... | |
double | interval |
INTERVAL. More... | |
CivilTime | lastObs |
TIME OF LAST OBS. More... | |
int | leapSeconds |
LEAP SECONDS. More... | |
RinexObsMap | mapObsTypes |
SYS / # / OBS TYPES. More... | |
VersionObsMap | mapSysR2toR3ObsID |
std::string | markerName |
MARKER NAME. More... | |
std::string | markerNumber |
MARKER NUMBER. More... | |
std::string | markerType |
MARKER TYPE. More... | |
PRNNumObsMap | numObsForSat |
PRN / # OF OBS. More... | |
short | numSVs |
std::string | observer |
who collected the data More... | |
RinexObsVec | obsTypeList |
bool | PisY |
Map P to Y code observations in RINEX 2 files. More... | |
bool | preserveDate |
bool | preserveVerType |
DisAmbMap | R2DisambiguityMap |
StringVec | R2ObsTypes |
int | receiverOffset |
RCV CLOCK OFFS APPL. More... | |
std::string | recNo |
receiver number More... | |
std::string | recType |
receiver type More... | |
std::string | recVers |
receiver version More... | |
std::string | sigStrengthUnit |
SIGNAL STRENGTH UNIT. More... | |
SysPhsShftMap | sysPhaseShift |
SYS / PHASE SHIFT. More... | |
SysScaleFacMap | sysSfacMap |
SYS / SCALE FACTOR. More... | |
Fields | valid |
bits set when header rec.s present & valid More... | |
bool | validEoH |
true if found END OF HEADER More... | |
double | version |
RINEX 3 version/type. More... | |
short | wavelengthFactor [2] |
WAVELENGTH FACT (system-wide) More... | |
XmitAnt | xmitAnt |
Non-standard, transmitter ID. More... | |
Static Public Attributes | |
static const GNSSTK_EXPORT Fields | allValid2 |
static const GNSSTK_EXPORT Fields | allValid30 |
static const GNSSTK_EXPORT Fields | allValid301 |
static const GNSSTK_EXPORT Fields | allValid302 |
static const GNSSTK_EXPORT Fields | allValid303 |
static GNSSTK_EXPORT int | debug = 0 |
Used to help debug this class. More... | |
RINEX observation file header formatting strings | |
static const GNSSTK_EXPORT std::string | hsVersion = "RINEX VERSION / TYPE" |
RINEX VERSION / TYPE. More... | |
static const GNSSTK_EXPORT std::string | hsRunBy = "PGM / RUN BY / DATE" |
PGM / RUN BY / DATE. More... | |
static const GNSSTK_EXPORT std::string | hsComment = "COMMENT" |
COMMENT. More... | |
static const GNSSTK_EXPORT std::string | hsMarkerName = "MARKER NAME" |
MARKER NAME. More... | |
static const GNSSTK_EXPORT std::string | hsMarkerNumber = "MARKER NUMBER" |
MARKER NUMBER. More... | |
static const GNSSTK_EXPORT std::string | hsMarkerType = "MARKER TYPE" |
MARKER TYPE. More... | |
static const GNSSTK_EXPORT std::string | hsObserver = "OBSERVER / AGENCY" |
OBSERVER / AGENCY. More... | |
static const GNSSTK_EXPORT std::string | hsReceiver = "REC # / TYPE / VERS" |
REC # / TYPE / VERS. More... | |
static const GNSSTK_EXPORT std::string | hsAntennaType = "ANT # / TYPE" |
ANT # / TYPE. More... | |
static const GNSSTK_EXPORT std::string | hsAntennaPosition = "APPROX POSITION XYZ" |
APPROX POSITION XYZ. More... | |
static const GNSSTK_EXPORT std::string | hsAntennaDeltaHEN = "ANTENNA: DELTA H/E/N" |
ANTENNA: DELTA H/E/N. More... | |
static const GNSSTK_EXPORT std::string | hsAntennaDeltaXYZ = "ANTENNA: DELTA X/Y/Z" |
ANTENNA: DELTA X/Y/Z. More... | |
static const GNSSTK_EXPORT std::string | hsAntennaPhaseCtr = "ANTENNA: PHASECENTER" |
ANTENNA: PHASECENTER. More... | |
static const GNSSTK_EXPORT std::string | hsAntennaBsightXYZ = "ANTENNA: B.SIGHT XYZ" |
ANTENNA: B.SIGHT XYZ. More... | |
static const GNSSTK_EXPORT std::string | hsAntennaZeroDirAzi = "ANTENNA: ZERODIR AZI" |
ANTENNA: ZERODIR AZI. More... | |
static const GNSSTK_EXPORT std::string | hsAntennaZeroDirXYZ = "ANTENNA: ZERODIR XYZ" |
ANTENNA: ZERODIR XYZ. More... | |
static const GNSSTK_EXPORT std::string | hsCenterOfMass = "CENTER OF MASS: XYZ" |
CENTER OF MASS: XYZ. More... | |
static const GNSSTK_EXPORT std::string | hsNumObs = "# / TYPES OF OBSERV" |
static const GNSSTK_EXPORT std::string | hsSystemNumObs = "SYS / # / OBS TYPES" |
SYS / # / OBS TYPES. More... | |
static const GNSSTK_EXPORT std::string | hsWaveFact = "WAVELENGTH FACT L1/2" |
WAVELENGTH FACT L1/2. More... | |
static const GNSSTK_EXPORT std::string | hsSigStrengthUnit = "SIGNAL STRENGTH UNIT" |
SIGNAL STRENGTH UNIT. More... | |
static const GNSSTK_EXPORT std::string | hsInterval = "INTERVAL" |
INTERVAL. More... | |
static const GNSSTK_EXPORT std::string | hsFirstTime = "TIME OF FIRST OBS" |
TIME OF FIRST OBS. More... | |
static const GNSSTK_EXPORT std::string | hsLastTime = "TIME OF LAST OBS" |
TIME OF LAST OBS. More... | |
static const GNSSTK_EXPORT std::string | hsReceiverOffset = "RCV CLOCK OFFS APPL" |
RCV CLOCK OFFS APPL. More... | |
static const GNSSTK_EXPORT std::string | hsSystemDCBSapplied = "SYS / DCBS APPLIED" |
SYS / DCBS APPLIED. More... | |
static const GNSSTK_EXPORT std::string | hsSystemPCVSapplied = "SYS / PCVS APPLIED" |
SYS / PCVS APPLIED. More... | |
static const GNSSTK_EXPORT std::string | hsSystemScaleFac = "SYS / SCALE FACTOR" |
SYS / SCALE FACTOR. More... | |
static const GNSSTK_EXPORT std::string | hsSystemPhaseShift = "SYS / PHASE SHIFT" |
SYS / PHASE SHIFT. More... | |
static const GNSSTK_EXPORT std::string | hsGlonassSlotFreqNo = "GLONASS SLOT / FRQ #" |
GLONASS SLOT / FRQ #. More... | |
static const GNSSTK_EXPORT std::string | hsGlonassCodPhsBias = "GLONASS COD/PHS/BIS" |
GLONASS COD/PHS/BIS. More... | |
static const GNSSTK_EXPORT std::string | hsLeapSeconds = "LEAP SECONDS" |
LEAP SECONDS. More... | |
static const GNSSTK_EXPORT std::string | hsNumSats = "# OF SATELLITES" |
static const GNSSTK_EXPORT std::string | hsPrnObs = "PRN / # OF OBS" |
PRN / # OF OBS. More... | |
static const GNSSTK_EXPORT std::string | hsEoH = "END OF HEADER" |
END OF HEADER. More... | |
static const GNSSTK_EXPORT std::string | hsAntennaStandard = "TRANSMITTER STANDARD" |
Fixed comment xmit ant. More... | |
static const GNSSTK_EXPORT std::string | hsAntennaRegional = "TRANSMITTER REGIONAL" |
Fixed comment xmit ant. More... | |
![]() | |
static const GNSSTK_EXPORT double | currentVersion = 3.04 |
Protected Member Functions | |
std::vector< RinexObsID > | mapR2ObsToR3Obs_E () |
std::vector< RinexObsID > | mapR2ObsToR3Obs_G () |
std::vector< RinexObsID > | mapR2ObsToR3Obs_R () |
std::vector< RinexObsID > | mapR2ObsToR3Obs_S () |
virtual void | reallyGetRecord (FFStream &s) |
virtual void | reallyPutRecord (FFStream &s) const |
void | remapObsTypes (RinexObsMap &remapped, std::map< std::string, unsigned > &obsCount) const |
Private Member Functions | |
CivilTime | parseTime (const std::string &line) const |
std::string | writeTime (const CivilTime &civtime) const |
Private Attributes | |
int | factor |
Scale factor holding data for continuation lines. More... | |
int | factorPrev |
RinexSatID | lastPRN |
save PRN while reading PRN/OBS cont. lines More... | |
int | numObs |
save OBS # / TYPES and Sys / SCALE FACTOR for continuation lines. More... | |
int | numObsPrev |
recall the prev # obs for cont. lines More... | |
std::string | satSysPrev |
recall the prev sat. sys for continuation lines. More... | |
std::string | satSysTemp |
save the syschar while reading ScaleFactor More... | |
RinexObsID | sysPhaseShiftObsID |
save ObsID for cont. "PHASE SHIFT" R3.01 More... | |
Friends | |
class | Rinex3ObsData |
typedef std::vector<Rinex3CorrInfo> gnsstk::Rinex3ObsHeader::CorrVec |
Corrections (e.g. code bias) vector.
Definition at line 360 of file Rinex3ObsHeader.hpp.
typedef std::map<std::string,std::string> gnsstk::Rinex3ObsHeader::DisAmbMap |
Map SysChar + R2 Obs Type to Obs ID.
Definition at line 358 of file Rinex3ObsHeader.hpp.
typedef std::vector<ExtraWaveFact> gnsstk::Rinex3ObsHeader::FactorVector |
Vector of wavelength factors.
Definition at line 362 of file Rinex3ObsHeader.hpp.
typedef std::set<Field> gnsstk::Rinex3ObsHeader::FieldSet |
Definition at line 363 of file Rinex3ObsHeader.hpp.
typedef std::map<RinexObsID, double> gnsstk::Rinex3ObsHeader::GLOCodPhsBias |
Map GLONASS SV observable to code phase bias.
Definition at line 356 of file Rinex3ObsHeader.hpp.
typedef std::map<RinexSatID, int> gnsstk::Rinex3ObsHeader::GLOFreqNumMap |
Map GLONASS SV ID to frequency number.
Definition at line 354 of file Rinex3ObsHeader.hpp.
typedef std::vector<int> gnsstk::Rinex3ObsHeader::IntVec |
Simple vector of ints.
Definition at line 327 of file Rinex3ObsHeader.hpp.
typedef std::map<std::string, RinexObsID> gnsstk::Rinex3ObsHeader::ObsIDMap |
Definition at line 344 of file Rinex3ObsHeader.hpp.
typedef std::map<RinexObsID, SVPhsShftMap> gnsstk::Rinex3ObsHeader::ObsPhsShftMap |
Map observation type to sv-phase shift map.
Definition at line 350 of file Rinex3ObsHeader.hpp.
typedef std::map<RinexSatID, IntVec> gnsstk::Rinex3ObsHeader::PRNNumObsMap |
Type used to count the number of observations for each observable.
Definition at line 329 of file Rinex3ObsHeader.hpp.
typedef std::map<std::string, RinexObsVec> gnsstk::Rinex3ObsHeader::RinexObsMap |
Map system to observables map <sys char, vec<ObsID> >; NB defines data vec in ObsData
Definition at line 342 of file Rinex3ObsHeader.hpp.
typedef std::vector<RinexObsID> gnsstk::Rinex3ObsHeader::RinexObsVec |
Vector of obervables.
Definition at line 338 of file Rinex3ObsHeader.hpp.
typedef std::map<RinexObsID, int> gnsstk::Rinex3ObsHeader::ScaleFacMap |
Scale Factor corrections for observations map <ObsType, ScaleFactor>
Definition at line 332 of file Rinex3ObsHeader.hpp.
typedef std::vector<std::string> gnsstk::Rinex3ObsHeader::StringVec |
Commonly used vector of strings.
Definition at line 325 of file Rinex3ObsHeader.hpp.
typedef std::map<RinexSatID, double> gnsstk::Rinex3ObsHeader::SVPhsShftMap |
Map satellite ID to phase shift.
Definition at line 348 of file Rinex3ObsHeader.hpp.
typedef std::map<std::string, ObsPhsShftMap> gnsstk::Rinex3ObsHeader::SysPhsShftMap |
Map system to observation type phase shift map.
Definition at line 352 of file Rinex3ObsHeader.hpp.
typedef std::map<std::string, ScaleFacMap> gnsstk::Rinex3ObsHeader::SysScaleFacMap |
Per-system scale factor corrections. Satellite system map of scale factor maps <(G/R/E/S), <Rinex3ObsType, scalefactor>>
Definition at line 336 of file Rinex3ObsHeader.hpp.
typedef std::map<std::string, ObsIDMap> gnsstk::Rinex3ObsHeader::VersionObsMap |
Definition at line 346 of file Rinex3ObsHeader.hpp.
Validity bits for the RINEX Observation Header - please keep ordered as strings above
Definition at line 246 of file Rinex3ObsHeader.hpp.
gnsstk::Rinex3ObsHeader::Rinex3ObsHeader | ( | ) |
A Simple Constructor.
Definition at line 173 of file Rinex3ObsHeader.cpp.
|
inlinevirtual |
Destructor.
Definition at line 554 of file Rinex3ObsHeader.hpp.
|
static |
Convert a RINEX header field label string into its matching enum.
Definition at line 2805 of file Rinex3ObsHeader.cpp.
|
static |
Return the RINEX header label for the given field enumeration.
Definition at line 2761 of file Rinex3ObsHeader.cpp.
void gnsstk::Rinex3ObsHeader::clear | ( | ) |
Clear (empty out) header, setting all data members to default values
Definition at line 180 of file Rinex3ObsHeader.cpp.
bool gnsstk::Rinex3ObsHeader::compare | ( | const Rinex3ObsHeader & | right, |
StringVec & | diffs, | ||
const StringVec & | inclExclList, | ||
bool | incl = false |
||
) |
Compare this header with another.
[in] | right | the header to compare this with. |
[out] | diffs | The header strings/identifiers that are different between this and right. |
[in] | inclExclList | a list of header strings to be ignored or used when making the comparison (e.g. "RINEX VERSION / TYPE"). |
[in] | incl | When true, only header lines listed in inclExclList will be compared. When false, differences in header lines in inclExclList will be ignored. |
Definition at line 2577 of file Rinex3ObsHeader.cpp.
|
inlinevirtual |
This is a debug output function which provides a lot of detail about the header contents, based on the value of version (RINEX format version).
Reimplemented from gnsstk::FFData.
Definition at line 568 of file Rinex3ObsHeader.hpp.
void gnsstk::Rinex3ObsHeader::dump | ( | std::ostream & | s, |
double | dumpVersion | ||
) | const |
This is a debug output function which provides a lot of detail about the header contents for a specified RINEX format version.
[in] | dumpVersion | The RINEX format version to use when dumping the contents of this header. Potentially affects the representation of obs IDs, as well as which header fields are printed. |
Definition at line 2253 of file Rinex3ObsHeader.cpp.
|
virtual |
This method returns the numerical index of a given observation
[in] | sys | GNSS system character for the obs |
[in] | obsID | RinexObsID of the observation |
InvalidRequest |
typedef std::vector<RinexObsID> RinexObsVec; typedef std::map<std::string, RinexObsVec> RinexObsMap; RinexObsMap mapObsTypes; ///< SYS / # / OBS TYPES
Definition at line 2545 of file Rinex3ObsHeader.cpp.
|
virtual |
This method returns the numerical index of a given observation
[in] | type | String representing the observation type. |
InvalidRequest |
Definition at line 2502 of file Rinex3ObsHeader.cpp.
|
inline |
Getter method for convenience of python bindings.
Definition at line 653 of file Rinex3ObsHeader.hpp.
|
inline |
Getter method for convenience of python bindings.
Definition at line 656 of file Rinex3ObsHeader.hpp.
|
inlinevirtual |
Rinex3ObsHeader is a "header" so this function always returns true.
Reimplemented from gnsstk::FFData.
Definition at line 561 of file Rinex3ObsHeader.hpp.
|
inline |
Return boolean : is this a valid Rinex header?
Definition at line 617 of file Rinex3ObsHeader.hpp.
|
protected |
Definition at line 1999 of file Rinex3ObsHeader.cpp.
|
protected |
Helper methods The conversion between RINEX v2.11 to RINEX v3 observation type is fraught with system-specific idiosyncracies. These methods read the list of v2.11 obs types stored in R2ObsTypes and attempt to build a corresponding list of v3 observation types where appropriate.
FFStreamError |
Definition at line 1821 of file Rinex3ObsHeader.cpp.
|
protected |
Definition at line 1940 of file Rinex3ObsHeader.cpp.
|
protected |
Definition at line 2061 of file Rinex3ObsHeader.cpp.
|
noexcept |
Compute number of valid header records that writeHeaderRecords() will write
Definition at line 293 of file Rinex3ObsHeader.cpp.
void gnsstk::Rinex3ObsHeader::parseHeaderRecord | ( | std::string & | line | ) |
Parse a single header record, and modify valid accordingly. Used by reallyGetRecord for both Rinex3ObsHeader and Rinex3ObsData.
FFStreamError |
< "SYS / PHASE SHIFT" R3.01
Definition at line 1066 of file Rinex3ObsHeader.cpp.
This function sets the time for this header. It looks at line to obtain the needed information.
Definition at line 2102 of file Rinex3ObsHeader.cpp.
void gnsstk::Rinex3ObsHeader::prepareVer2Write | ( | void | ) |
Compute map of obs types for use in writing version 2 header and data
Definition at line 2141 of file Rinex3ObsHeader.cpp.
|
protectedvirtual |
This function retrieves the RINEX Header from the given FFStream. If an stream error is encountered, the stream is reset to its original position and its fail-bit is set.
std::exception | |
StringException | when a StringUtils function fails |
FFStreamError | when exceptions(failbit) is set and a read or formatting error occurs. This also resets the stream to its pre-read position. |
Implements gnsstk::FFData.
Definition at line 1596 of file Rinex3ObsHeader.cpp.
|
protectedvirtual |
outputs this record to the stream correctly formatted.
std::exception | |
FFStreamError | |
StringUtils::StringException |
Implements gnsstk::FFData.
Definition at line 249 of file Rinex3ObsHeader.cpp.
|
protected |
Because of how pseudo-observables are handled, we need this function to remap the contents of mapObsTypes such that ionospheric delay and channel pseudo-observables get the treatment they need.
Definition at line 2858 of file Rinex3ObsHeader.cpp.
|
inline |
Setter method for convenience of python bindings.
Definition at line 646 of file Rinex3ObsHeader.hpp.
void gnsstk::Rinex3ObsHeader::writeHeaderRecords | ( | FFStream & | s | ) | const |
Write all valid header records to the given stream. Used by reallyPutRecord for both Rinex3ObsHeader and Rinex3ObsData.
FFStreamError | |
StringUtils::StringException |
Definition at line 345 of file Rinex3ObsHeader.cpp.
Converts the daytime dt into a Rinex Obs time string for the header
Definition at line 2123 of file Rinex3ObsHeader.cpp.
|
friend |
Definition at line 700 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::agency |
observer's agency
Definition at line 503 of file Rinex3ObsHeader.hpp.
|
static |
Definition at line 464 of file Rinex3ObsHeader.hpp.
|
static |
Definition at line 464 of file Rinex3ObsHeader.hpp.
|
static |
Definition at line 464 of file Rinex3ObsHeader.hpp.
|
static |
Definition at line 464 of file Rinex3ObsHeader.hpp.
|
static |
Definition at line 465 of file Rinex3ObsHeader.hpp.
gnsstk::Triple gnsstk::Rinex3ObsHeader::antennaBsightXYZ |
ANTENNA B.SIGHT XYZ.
Definition at line 515 of file Rinex3ObsHeader.hpp.
gnsstk::Triple gnsstk::Rinex3ObsHeader::antennaDeltaHEN |
ANTENNA: DELTA H/E/N.
Definition at line 510 of file Rinex3ObsHeader.hpp.
gnsstk::Triple gnsstk::Rinex3ObsHeader::antennaDeltaXYZ |
ANTENNA: DELTA X/Y/Z.
Definition at line 511 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::antennaObsCode |
ANTENNA P.CTR BLOCK: OBS CODE.
Definition at line 513 of file Rinex3ObsHeader.hpp.
gnsstk::Triple gnsstk::Rinex3ObsHeader::antennaPhaseCtr |
ANTENNA P.CTR BLOCK: PCTR POS.
Definition at line 514 of file Rinex3ObsHeader.hpp.
gnsstk::Triple gnsstk::Rinex3ObsHeader::antennaPosition |
APPROX POSITION XYZ.
Definition at line 509 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::antennaSatSys |
ANTENNA P.CTR BLOCK: SAT SYS.
Definition at line 512 of file Rinex3ObsHeader.hpp.
double gnsstk::Rinex3ObsHeader::antennaZeroDirAzi |
ANTENNA ZERODIR AZI.
Definition at line 516 of file Rinex3ObsHeader.hpp.
gnsstk::Triple gnsstk::Rinex3ObsHeader::antennaZeroDirXYZ |
ANTENNA ZERODIR XYZ.
Definition at line 517 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::antNo |
antenna number
Definition at line 507 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::antType |
antenna type
Definition at line 508 of file Rinex3ObsHeader.hpp.
gnsstk::Triple gnsstk::Rinex3ObsHeader::centerOfMass |
vehicle CENTER OF MASS: XYZ
Definition at line 518 of file Rinex3ObsHeader.hpp.
StringVec gnsstk::Rinex3ObsHeader::commentList |
comments in header
Definition at line 498 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::date |
when program was run
Definition at line 493 of file Rinex3ObsHeader.hpp.
|
static |
Used to help debug this class.
Definition at line 551 of file Rinex3ObsHeader.hpp.
FactorVector gnsstk::Rinex3ObsHeader::extraWaveFactList |
WAVELENGTH FACT (per SV)
Definition at line 521 of file Rinex3ObsHeader.hpp.
|
private |
Scale factor holding data for continuation lines.
Definition at line 726 of file Rinex3ObsHeader.hpp.
|
private |
Definition at line 726 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::fileAgency |
who ran program
Definition at line 492 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::fileProgram |
program used to generate file
Definition at line 491 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::fileSys |
file sys char: RinexSatID system OR Mixed
Definition at line 484 of file Rinex3ObsHeader.hpp.
SatID gnsstk::Rinex3ObsHeader::fileSysSat |
fileSys as a SatID
Definition at line 490 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::fileType |
RINEX 3 file type
Definition at line 482 of file Rinex3ObsHeader.hpp.
CivilTime gnsstk::Rinex3ObsHeader::firstObs |
TIME OF FIRST OBS.
Definition at line 524 of file Rinex3ObsHeader.hpp.
GLOCodPhsBias gnsstk::Rinex3ObsHeader::glonassCodPhsBias |
GLONASS COD/PHS/BIS.
Definition at line 532 of file Rinex3ObsHeader.hpp.
GLOFreqNumMap gnsstk::Rinex3ObsHeader::glonassFreqNo |
GLONASS SLOT / FRQ #.
Definition at line 531 of file Rinex3ObsHeader.hpp.
|
static |
ANTENNA: B.SIGHT XYZ.
Definition at line 195 of file Rinex3ObsHeader.hpp.
|
static |
ANTENNA: DELTA H/E/N.
Definition at line 189 of file Rinex3ObsHeader.hpp.
|
static |
ANTENNA: DELTA X/Y/Z.
Definition at line 191 of file Rinex3ObsHeader.hpp.
|
static |
ANTENNA: PHASECENTER.
Definition at line 193 of file Rinex3ObsHeader.hpp.
|
static |
APPROX POSITION XYZ.
Definition at line 187 of file Rinex3ObsHeader.hpp.
|
static |
Fixed comment xmit ant.
Definition at line 241 of file Rinex3ObsHeader.hpp.
|
static |
Fixed comment xmit ant.
Definition at line 239 of file Rinex3ObsHeader.hpp.
|
static |
ANT # / TYPE.
Definition at line 185 of file Rinex3ObsHeader.hpp.
|
static |
ANTENNA: ZERODIR AZI.
Definition at line 197 of file Rinex3ObsHeader.hpp.
|
static |
ANTENNA: ZERODIR XYZ.
Definition at line 199 of file Rinex3ObsHeader.hpp.
|
static |
CENTER OF MASS: XYZ.
Definition at line 201 of file Rinex3ObsHeader.hpp.
|
static |
COMMENT.
Definition at line 173 of file Rinex3ObsHeader.hpp.
|
static |
END OF HEADER.
Definition at line 237 of file Rinex3ObsHeader.hpp.
|
static |
TIME OF FIRST OBS.
Definition at line 213 of file Rinex3ObsHeader.hpp.
|
static |
GLONASS COD/PHS/BIS.
Definition at line 229 of file Rinex3ObsHeader.hpp.
|
static |
GLONASS SLOT / FRQ #.
Definition at line 227 of file Rinex3ObsHeader.hpp.
|
static |
INTERVAL.
Definition at line 211 of file Rinex3ObsHeader.hpp.
|
static |
TIME OF LAST OBS.
Definition at line 215 of file Rinex3ObsHeader.hpp.
|
static |
LEAP SECONDS.
Definition at line 231 of file Rinex3ObsHeader.hpp.
|
static |
MARKER NAME.
Definition at line 175 of file Rinex3ObsHeader.hpp.
|
static |
MARKER NUMBER.
Definition at line 177 of file Rinex3ObsHeader.hpp.
|
static |
MARKER TYPE.
Definition at line 179 of file Rinex3ObsHeader.hpp.
|
static |
Definition at line 203 of file Rinex3ObsHeader.hpp.
|
static |
Definition at line 233 of file Rinex3ObsHeader.hpp.
|
static |
OBSERVER / AGENCY.
Definition at line 181 of file Rinex3ObsHeader.hpp.
|
static |
PRN / # OF OBS.
Definition at line 235 of file Rinex3ObsHeader.hpp.
|
static |
REC # / TYPE / VERS.
Definition at line 183 of file Rinex3ObsHeader.hpp.
|
static |
RCV CLOCK OFFS APPL.
Definition at line 217 of file Rinex3ObsHeader.hpp.
|
static |
PGM / RUN BY / DATE.
Definition at line 171 of file Rinex3ObsHeader.hpp.
|
static |
SIGNAL STRENGTH UNIT.
Definition at line 209 of file Rinex3ObsHeader.hpp.
|
static |
SYS / DCBS APPLIED.
Definition at line 219 of file Rinex3ObsHeader.hpp.
|
static |
SYS / # / OBS TYPES.
Definition at line 205 of file Rinex3ObsHeader.hpp.
|
static |
SYS / PCVS APPLIED.
Definition at line 221 of file Rinex3ObsHeader.hpp.
|
static |
SYS / PHASE SHIFT.
Definition at line 225 of file Rinex3ObsHeader.hpp.
|
static |
SYS / SCALE FACTOR.
Definition at line 223 of file Rinex3ObsHeader.hpp.
|
static |
RINEX VERSION / TYPE.
Definition at line 169 of file Rinex3ObsHeader.hpp.
|
static |
WAVELENGTH FACT L1/2.
Definition at line 207 of file Rinex3ObsHeader.hpp.
CorrVec gnsstk::Rinex3ObsHeader::infoDCBS |
DCBS INFO.
Definition at line 527 of file Rinex3ObsHeader.hpp.
CorrVec gnsstk::Rinex3ObsHeader::infoPCVS |
PCVS INFO.
Definition at line 528 of file Rinex3ObsHeader.hpp.
double gnsstk::Rinex3ObsHeader::interval |
INTERVAL.
Definition at line 523 of file Rinex3ObsHeader.hpp.
CivilTime gnsstk::Rinex3ObsHeader::lastObs |
TIME OF LAST OBS.
Definition at line 525 of file Rinex3ObsHeader.hpp.
|
private |
save PRN while reading PRN/OBS cont. lines
Definition at line 724 of file Rinex3ObsHeader.hpp.
int gnsstk::Rinex3ObsHeader::leapSeconds |
LEAP SECONDS.
Definition at line 533 of file Rinex3ObsHeader.hpp.
RinexObsMap gnsstk::Rinex3ObsHeader::mapObsTypes |
SYS / # / OBS TYPES.
Definition at line 519 of file Rinex3ObsHeader.hpp.
VersionObsMap gnsstk::Rinex3ObsHeader::mapSysR2toR3ObsID |
map between RINEX ver 3 ObsIDs and ver 2 obstypes for each system: reallyPut
Definition at line 475 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::markerName |
MARKER NAME.
Definition at line 499 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::markerNumber |
MARKER NUMBER.
Definition at line 500 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::markerType |
MARKER TYPE.
Definition at line 501 of file Rinex3ObsHeader.hpp.
|
private |
save OBS # / TYPES and Sys / SCALE FACTOR for continuation lines.
Definition at line 720 of file Rinex3ObsHeader.hpp.
PRNNumObsMap gnsstk::Rinex3ObsHeader::numObsForSat |
PRN / # OF OBS.
Definition at line 535 of file Rinex3ObsHeader.hpp.
|
private |
recall the prev # obs for cont. lines
Definition at line 722 of file Rinex3ObsHeader.hpp.
short gnsstk::Rinex3ObsHeader::numSVs |
Definition at line 534 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::observer |
who collected the data
Definition at line 502 of file Rinex3ObsHeader.hpp.
RinexObsVec gnsstk::Rinex3ObsHeader::obsTypeList |
number & types of observations R2 only
Definition at line 541 of file Rinex3ObsHeader.hpp.
bool gnsstk::Rinex3ObsHeader::PisY |
Map P to Y code observations in RINEX 2 files.
Definition at line 548 of file Rinex3ObsHeader.hpp.
bool gnsstk::Rinex3ObsHeader::preserveDate |
If false, the current system time will be used when writing the header, otherwise the value in date will be used.
Definition at line 497 of file Rinex3ObsHeader.hpp.
bool gnsstk::Rinex3ObsHeader::preserveVerType |
If false, the file type and system will be re-generated in the gnsstk preferred format when writing the header, otherwise the strings fileType fileSys will be written unaltered
Definition at line 489 of file Rinex3ObsHeader.hpp.
DisAmbMap gnsstk::Rinex3ObsHeader::R2DisambiguityMap |
map Sys + R2ot to their ObsID origins
Definition at line 478 of file Rinex3ObsHeader.hpp.
StringVec gnsstk::Rinex3ObsHeader::R2ObsTypes |
Storage for R2 <-> R3 conversion of obstypes during reallyGet/Put Vector of strings containing ver 2 obs types (e.g. "C1" "L2") defined in reallyGet; also defined in PrepareVer2Write() from R3 ObsIDs
Definition at line 471 of file Rinex3ObsHeader.hpp.
int gnsstk::Rinex3ObsHeader::receiverOffset |
RCV CLOCK OFFS APPL.
Definition at line 526 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::recNo |
receiver number
Definition at line 504 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::recType |
receiver type
Definition at line 505 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::recVers |
receiver version
Definition at line 506 of file Rinex3ObsHeader.hpp.
|
private |
recall the prev sat. sys for continuation lines.
Definition at line 718 of file Rinex3ObsHeader.hpp.
|
private |
save the syschar while reading ScaleFactor
Definition at line 716 of file Rinex3ObsHeader.hpp.
std::string gnsstk::Rinex3ObsHeader::sigStrengthUnit |
SIGNAL STRENGTH UNIT.
Definition at line 522 of file Rinex3ObsHeader.hpp.
SysPhsShftMap gnsstk::Rinex3ObsHeader::sysPhaseShift |
SYS / PHASE SHIFT.
Definition at line 530 of file Rinex3ObsHeader.hpp.
|
private |
save ObsID for cont. "PHASE SHIFT" R3.01
Definition at line 714 of file Rinex3ObsHeader.hpp.
SysScaleFacMap gnsstk::Rinex3ObsHeader::sysSfacMap |
SYS / SCALE FACTOR.
Definition at line 529 of file Rinex3ObsHeader.hpp.
Fields gnsstk::Rinex3ObsHeader::valid |
bits set when header rec.s present & valid
Definition at line 544 of file Rinex3ObsHeader.hpp.
bool gnsstk::Rinex3ObsHeader::validEoH |
true if found END OF HEADER
Definition at line 546 of file Rinex3ObsHeader.hpp.
double gnsstk::Rinex3ObsHeader::version |
RINEX 3 version/type.
Definition at line 481 of file Rinex3ObsHeader.hpp.
short gnsstk::Rinex3ObsHeader::wavelengthFactor[2] |
WAVELENGTH FACT (system-wide)
Definition at line 520 of file Rinex3ObsHeader.hpp.
XmitAnt gnsstk::Rinex3ObsHeader::xmitAnt |
Non-standard, transmitter ID.
Definition at line 537 of file Rinex3ObsHeader.hpp.