|
short | accuracy2CNAVura (double acc) noexcept |
|
short | accuracy2ura (double acc) noexcept |
|
double | ADtest (double *xd, const int nd, double m, double s, bool save_flag=true) |
|
double | ARand (double low, double hi) |
|
int | ARand (int low, int hi) |
|
double | beta (double x, double y) |
|
double | binomialCoeff (int n, int k) |
|
Matrix< T > | blkdiag (const ConstMatrixBase< T, BaseClass > &m1, const ConstMatrixBase< T, BaseClass > &m2) |
|
Matrix< T > | blkdiag (const ConstMatrixBase< T, BaseClass > &m1, const ConstMatrixBase< T, BaseClass > &m2, const ConstMatrixBase< T, BaseClass > &m3) |
|
Matrix< T > | blkdiag (const ConstMatrixBase< T, BaseClass > &m1, const ConstMatrixBase< T, BaseClass > &m2, const ConstMatrixBase< T, BaseClass > &m3, const ConstMatrixBase< T, BaseClass > &m4) |
|
double | cel2far (double c) |
|
double | cfIBeta (double x, double a, double b) |
|
double | ChisqCDF (double x, int n) |
|
double | ChisqPDF (double x, int n) |
|
double | compErrorFunc (double x) |
|
double | compIncompGamma (double a, double x) |
|
static void | computeFundamentalArgs (double T, double args[6]) |
|
Triple | computePolarTides (const Position &site, const EphTime &ttag, double xp, double yp, const IERSConvention &iers) |
|
Triple | computeSolidEarthTides (const Position &site, const EphTime &ttag, const Position &Sun, const Position &Moon, double EMRAT, double SERAT, const IERSConvention &iers) |
|
T | condNum (const ConstMatrixBase< T, BaseClass > &m) noexcept |
|
T | condNum (const ConstMatrixBase< T, BaseClass > &m, T &bigNum, T &smallNum) noexcept |
|
double | contfracIncompGamma (double a, double x) |
|
long | convertCalendarToJD (int yy, int mm, int dd) |
|
void | convertJDtoCalendar (long jd, int &iyear, int &imonth, int &iday) |
|
std::string | convertNavTypeToString (NavType e) |
|
std::string | convertSatelliteSystemToString (SatelliteSystem s) |
|
void | convertSODtoTime (double sod, int &hh, int &mm, double &sec) |
|
NavType | convertStringToNavType (const std::string &s) |
|
SatelliteSystem | convertStringToSatelliteSystem (const std::string &s) |
|
double | convertTimeToSOD (int hh, int mm, double sec) |
|
static void | correctEarthRotationLibrations (const double args[6], double &dUT, double &dld) |
|
static void | correctEarthRotationZonalTides (const double args[6], double &dUT, double &dld, double &dom) |
|
static void | correctEarthRotationZonalTides2003 (const double args[6], double &dUT, double &dld, double &dom) |
|
static void | correctEOPOceanTides (double mjd, double &dxp, double &dyp, double &dUT) |
|
T | cosVec (const ConstVectorBase< T, BaseClass1 > &a, const ConstVectorBase< T, BaseClass2 > &b) |
|
T | cosVec (const SparseVector< T > &S1, const SparseVector< T > &S2) |
|
T | cosVec (const SparseVector< T > &SV, const Vector< T > &V) |
|
T | cosVec (const Vector< T > &V, const SparseVector< T > &SV) |
|
class BaseClass2 Vector< T > | cross (const ConstVectorBase< T, BaseClass > &l, const ConstVectorBase< T, BaseClass2 > &r) |
|
void | crudeSolarPosition (const CommonTime &t, double &lat, double &lon) |
|
double | cycles2meters (double phase, double freq, EllipsoidModel &ellipsoid) |
|
std::string | demangle (const char *name) |
|
T | det (const ConstMatrixBase< T, BaseClass > &m) |
|
Matrix< T > | diag (const ConstMatrixBase< T, BaseClass > &m) |
|
int | DiscontinuityCorrector (SatPass &SP, GDCconfiguration &config, std::vector< std::string > &EditCmds, std::string &retMsg, int GLOn=-99) |
|
void | DisplayExtendedRinexObsTypes (ostream &s) |
|
void | DisplayExtendedRinexObsTypes (std::ostream &s) |
|
void | DisplayStandardRinexObsTypes (ostream &s) |
|
void | DisplayStandardRinexObsTypes (std::ostream &s) |
|
void | DMsmootherUpdateWithControl (Matrix< double > &P, Vector< double > &X, Matrix< double > &Phinv, Matrix< double > &Rw, Matrix< double > &G, Vector< double > &Zw, Matrix< double > &Rwx, Vector< double > &U) |
|
T | dot (const ConstVectorBase< T, BaseClass > &l, const ConstVectorBase< T, BaseClass2 > &r) |
|
T | dot (const ConstVectorBase< T, BaseClass > &l, const T r) |
|
T | dot (const SparseVector< T > &SL, const SparseVector< T > &SR) |
|
T | dot (const SparseVector< T > &SL, const Vector< T > &R) |
|
T | dot (const T l, const ConstVectorBase< T, BaseClass > &r) |
|
T | dot (const Vector< T > &L, const SparseVector< T > &SR) |
|
T | dot_lim (const SparseVector< T > &SL, const SparseVector< T > &SR, const unsigned int kb, const unsigned int ke) |
|
void | dump (std::vector< SatPass > &SatPassList, std::ostream &os, bool rev=false, bool dbug=false) |
|
void | dump (vector< SatPass > &SatPassList, ostream &os, bool rev, bool dbug) |
|
void | dumpAllRinex3ObsTypes (ostream &os) |
|
void | dumpAllRinex3ObsTypes (std::ostream &s) |
|
T | errfc (T x) |
|
double | errorFunc (double x) |
|
void | expand_args (vector< string > &oldvalues, vector< string > &newvalues, string &msg) |
|
void | expand_filename (std::string &filename) |
|
void | expand_filename (std::vector< std::string > &sarray) |
|
void | expand_filename (string &filename) |
|
void | expand_filename (vector< string > &sarray) |
|
bool | expand_list_file (std::string &filename, std::vector< std::string > &values) |
|
bool | expand_list_file (string &filename, vector< string > &values) |
|
double | factorial (int n) |
|
double | far2cel (double f) |
|
double | FDistCDF (double F, int n1, int n2) |
|
double | FDistPDF (double x, int n1, int n2) |
|
int | findMilliseconds (std::vector< SatPass > &SPList, msecHandler &msh) |
|
int | findMilliseconds (vector< SatPass > &SPList, msecHandler &msh) |
|
double | Gamma (double x) |
|
double | getAlpha (SatelliteSystem sys, int na, int nb) noexcept |
|
double | getBeta (SatelliteSystem sys, int na, int nb) noexcept |
|
double | getFrequency (CarrierBand band) |
|
double | getGamma (CarrierBand band1, CarrierBand band2) |
|
double | getLeapSeconds (const int year, const int month, const double day) |
|
short | getLegacyFitInterval (const short iodc, const short fiti) |
|
RefFrameRlz | getRefFrameRlz (RefFrameSys sys, const CommonTime &when) |
|
RefFrameSys | getRefFrameSys (RefFrameRlz rlz) noexcept |
|
double | getTimeSystemCorrection (const TimeSystem inTS, const TimeSystem outTS, const int year, const int month, const double day) |
|
double | getWavelength (SatelliteSystem sys, int rinexBandNum, int gloChan=0) noexcept |
|
static double | GMST (const CommonTime &t) |
|
double | hg2mb (double hg) |
|
BaseClass & | ident (RefMatrixBase< T, BaseClass > &m) |
|
Matrix< T > | ident (size_t dim) |
|
bool | identical (const Namelist &N1, const Namelist &N2) |
|
SparseMatrix< T > | identSparse (const unsigned int dim) |
|
void | include_path (std::string path, std::string &file) |
|
void | include_path (std::string path, std::vector< std::string > &sarray) |
|
void | include_path (string path, string &file) |
|
void | include_path (string path, vector< string > &sarray) |
|
double | incompGamma (double a, double x) |
|
double | incompleteBeta (double x, double a, double b) |
|
void | insert (T *sa, int na, int(*comp)(const T &, const T &)=gnsstk::Qsort_compare) |
|
void | insert (T *sa, S *pa, int na, int(*comp)(const T &, const T &)=gnsstk::Qsort_compare) |
|
string | int2bin (unsigned int v, int len=8) |
|
double | invChisqCDF (double alpha, int n) |
|
Matrix< T > | inverse (const ConstMatrixBase< T, BaseClass > &m) |
|
SparseMatrix< T > | inverse (const SparseMatrix< T > &A) |
|
Matrix< T > | inverseChol (const ConstMatrixBase< T, BaseClass > &m) |
|
Matrix< T > | inverseCholesky (const Matrix< T > &A) |
|
Matrix< T > | inverseLT (const Matrix< T > <, T *ptrSmall=NULL, T *ptrBig=NULL) |
|
SparseMatrix< T > | inverseLT (const SparseMatrix< T > &L, T *ptrSmall, T *ptrBig) |
|
Matrix< T > | inverseLUD (const ConstMatrixBase< T, BaseClass > &m) |
|
Matrix< T > | inverseLUD (const ConstMatrixBase< T, BaseClass > &m, T &determ) |
|
Matrix< T > | inverseSVD (const ConstMatrixBase< T, BaseClass > &m, const T tol=T(1.e-8)) |
|
Matrix< T > | inverseSVD (const ConstMatrixBase< T, BaseClass > &m, T &bigNum, T &smallNum, const T tol=T(1.e-8)) |
|
Matrix< T > | inverseSVD (const ConstMatrixBase< T, BaseClass > &m, Vector< T > &sv, const T tol=T(1.e-8)) |
|
Matrix< T > | inverseUT (const Matrix< T > &UT, T *ptrSmall=NULL, T *ptrBig=NULL) |
|
SparseMatrix< T > | inverseViaCholesky (const SparseMatrix< T > &A) |
|
double | invFDistCDF (double prob, int n1, int n2) |
|
double | invNormalCDF (double prob, double mu, double sig) |
|
double | invStudentsCDF (double prob, int n) |
|
bool | isBeiDouGEO (const SatID &sat) |
|
bool | isRinex3NavFile (const std::string &file) |
|
bool | isRinex3NavFile (const string &file) |
|
bool | isRinex3ObsFile (const std::string &file) |
|
bool | isRinex3ObsFile (const string &file) |
|
bool | isRinexNavFile (const std::string &file) |
|
bool | isRinexNavFile (const string &file) |
|
bool | isRinexObsFile (const std::string &file) |
|
bool | isRinexObsFile (const string &file) |
|
bool | isSP3File (const std::string &file) |
|
bool | isSP3File (const string &file) |
|
bool | isValidRinexObsID (const std::string &id, const char syschar) |
|
bool | isValidRinexObsID (const std::string &strID) |
|
T | LagrangeInterpolating2ndDerivative (const std::vector< T > &pos, const std::vector< T > &val, const T desiredPos) |
|
T | LagrangeInterpolation (const std::vector< T > &X, const std::vector< T > &Y, const T &x, T &err) |
|
void | LagrangeInterpolation (const std::vector< T > &X, const std::vector< T > &Y, const T &x, T &y, T &dydx) |
|
Matrix< T > | LDL (const Matrix< T > &A, Vector< T > &D) |
|
double | lnFactorial (int n) |
|
double | lnGamma (double x) |
|
Matrix< T > | lowerCholesky (const Matrix< T > &A, const T ztol=T(1.e-16)) |
|
SparseMatrix< T > | lowerCholesky (const SparseMatrix< T > &A) |
|
Position | lunarPosition (const CommonTime &t, double &AR) |
|
T | mad (const gnsstk::Vector< T > &v) |
|
T | mad (const std::vector< T > &v) |
|
SparseMatrix< T > | matrixTimesTranspose (const SparseMatrix< T > &M) |
|
T | max (const ConstVectorBase< T, BaseClass > &l) |
|
T | max (const SparseMatrix< T > &SM) |
|
T | max (const SparseVector< T > &SV) |
|
For | max (const std::list< For > &lst) |
|
T | maxabs (const ConstMatrixBase< T, BaseClass > &a) noexcept |
|
T | maxabs (const ConstVectorBase< T, BaseClass > &l) |
|
T | maxabs (const SparseMatrix< T > &SM) |
|
T | maxabs (const SparseVector< T > &SV) |
|
double | mb2hg (double mb) |
|
T | median (const std::vector< T > &v) |
|
T | median (const Vector< T > &v) |
|
double | meters2cycles (double range, double freq, EllipsoidModel &ellipsoid) |
|
T | min (const ConstVectorBase< T, BaseClass > &l) |
|
T | min (const SparseMatrix< T > &SM) |
|
T | min (const SparseVector< T > &SV) |
|
For | min (const std::list< For > &lst) |
|
T | minabs (const ConstVectorBase< T, BaseClass > &l) |
|
T | minabs (const SparseMatrix< T > &SM) |
|
T | minabs (const SparseVector< T > &SV) |
|
T | Minkowski (const ConstVectorBase< T, BaseClass > &v, const ConstVectorBase< T, BaseClass2 > &w) |
|
Matrix< T > | minorMatrix (const ConstMatrixBase< T, BaseClass > &l, size_t row, size_t col) |
|
void | mixedScanTime (CommonTime &t, const std::string &str, const std::string &fmt) |
|
void | mixedScanTime (CommonTime &t, const string &str, const string &fmt) |
|
static double | NB_Interpolate (double lat, int doy, TableEntry entry) |
|
| NEW_EXCEPTION_CLASS (AccessError, Exception) |
|
| NEW_EXCEPTION_CLASS (AssertionFailure, Exception) |
|
| NEW_EXCEPTION_CLASS (ConfigurationException, Exception) |
|
| NEW_EXCEPTION_CLASS (EndOfFile, gnsstk::FFStreamError) |
|
| NEW_EXCEPTION_CLASS (ExpressionException, Exception) |
|
| NEW_EXCEPTION_CLASS (FFStreamError, gnsstk::Exception) |
|
| NEW_EXCEPTION_CLASS (FileMissingException, Exception) |
|
| NEW_EXCEPTION_CLASS (FileSpecException, gnsstk::Exception) |
|
| NEW_EXCEPTION_CLASS (GeometryException, gnsstk::Exception) |
|
| NEW_EXCEPTION_CLASS (IndexOutOfBoundsException, Exception) |
|
| NEW_EXCEPTION_CLASS (InvalidArgumentException, Exception) |
|
| NEW_EXCEPTION_CLASS (InvalidParameter, Exception) |
|
| NEW_EXCEPTION_CLASS (InvalidRequest, Exception) |
|
| NEW_EXCEPTION_CLASS (InvalidTropModel, gnsstk::Exception) |
|
| NEW_EXCEPTION_CLASS (InvalidValue, gnsstk::Exception) |
|
| NEW_EXCEPTION_CLASS (MatrixException, Exception) |
|
| NEW_EXCEPTION_CLASS (NoNAVSTARNumberFound, gnsstk::Exception) |
|
| NEW_EXCEPTION_CLASS (NoPRNNumberFound, gnsstk::Exception) |
|
| NEW_EXCEPTION_CLASS (NullPointerException, Exception) |
|
| NEW_EXCEPTION_CLASS (ObjectNotFound, AccessError) |
|
| NEW_EXCEPTION_CLASS (OutOfMemory, Exception) |
|
| NEW_EXCEPTION_CLASS (SingularMatrixException, MatrixException) |
|
| NEW_EXCEPTION_CLASS (SVNotPresentException, gnsstk::InvalidRequest) |
|
| NEW_EXCEPTION_CLASS (SystemPipeException, Exception) |
|
| NEW_EXCEPTION_CLASS (SystemQueueException, Exception) |
|
| NEW_EXCEPTION_CLASS (SystemSemaphoreException, Exception) |
|
| NEW_EXCEPTION_CLASS (UnimplementedException, Exception) |
|
| NEW_EXCEPTION_CLASS (VectorException, gnsstk::Exception) |
|
short | nominalAccuracy2ura (double acc) noexcept |
|
T | norm (const ConstVectorBase< T, BaseClass > &v) |
|
T | norm (const SparseVector< T > &SV) |
|
double | NormalCDF (double x, double mu, double sig) |
|
T | normalCDF (T m, T s, T x) |
|
Vector< T > | normalize (const ConstVectorBase< T, BaseClass > &l) |
|
double | NormalPDF (double x, double mu, double sig) |
|
T | normCol (const ConstMatrixBase< T, BaseClass > &m) |
|
T | normF (const ConstMatrixBase< T, BaseClass > &m) |
|
Matrix< double > | northEastUp (Position &pos, bool geocentric) |
|
Matrix< double > | northEastUpGeocentric (Position &pos) |
|
Matrix< double > | northEastUpGeodetic (Position &pos) |
|
bool | operator!= (const IonexData::IonexValType &x, const IonexData::IonexValType &y) |
|
bool | operator!= (const Namelist &N1, const Namelist &N2) |
|
Namelist | operator& (const Namelist &N1, const Namelist &N2) |
|
Matrix< T > | operator&& (const ConstMatrixBase< T, BaseClass1 > &l, const ConstMatrixBase< T, BaseClass2 > &r) |
|
Matrix< T > | operator&& (const ConstMatrixBase< T, BaseClass1 > &t, const ConstVectorBase< T, BaseClass2 > &b) |
|
Matrix< T > | operator&& (const ConstVectorBase< T, BaseClass1 > &t, const ConstMatrixBase< T, BaseClass2 > &b) |
|
Matrix< T > | operator* (const ConstMatrixBase< T, BaseClass > &m, const T d) |
|
Matrix< T > | operator* (const ConstMatrixBase< T, BaseClass1 > &l, const ConstMatrixBase< T, BaseClass2 > &r) |
|
Vector< T > | operator* (const ConstMatrixBase< T, BaseClass1 > &m, const ConstVectorBase< T, BaseClass2 > &v) |
|
Vector< T > | operator* (const ConstVectorBase< T, BaseClass1 > &v, const ConstMatrixBase< T, BaseClass2 > &m) |
|
SparseMatrix< T > | operator* (const Matrix< T > &L, const SparseMatrix< T > &R) |
|
SparseVector< T > | operator* (const Matrix< T > &L, const SparseVector< T > &V) |
|
SparseMatrix< T > | operator* (const SparseMatrix< T > &L, const Matrix< T > &R) |
|
SparseMatrix< T > | operator* (const SparseMatrix< T > &L, const SparseMatrix< T > &R) |
|
SparseVector< T > | operator* (const SparseMatrix< T > &L, const SparseVector< T > &V) |
|
SparseVector< T > | operator* (const SparseMatrix< T > &L, const Vector< T > &V) |
|
SparseVector< T > | operator* (const SparseVector< T > &V, const Matrix< T > &R) |
|
SparseVector< T > | operator* (const SparseVector< T > &V, const SparseMatrix< T > &R) |
|
Matrix< T > | operator* (const T d, const ConstMatrixBase< T, BaseClass > &m) |
|
SparseVector< T > | operator* (const Vector< T > &V, const SparseMatrix< T > &R) |
|
Triple | operator* (double scale, const Triple &rhs) |
|
Matrix< T > | operator+ (const ConstMatrixBase< T, BaseClass > &m, const T d) |
|
Matrix< T > | operator+ (const ConstMatrixBase< T, BaseClass1 > &l, const ConstMatrixBase< T, BaseClass2 > &r) |
|
SparseMatrix< T > | operator+ (const Matrix< T > &L, const SparseMatrix< T > &R) |
|
Position | operator+ (const Position &left, const Position &right) noexcept |
|
SparseMatrix< T > | operator+ (const SparseMatrix< T > &L, const Matrix< T > &R) |
|
SparseMatrix< T > | operator+ (const SparseMatrix< T > &L, const SparseMatrix< T > &R) |
|
SparseVector< T > | operator+ (const SparseVector< T > &L, const SparseVector< T > &R) |
|
SparseVector< T > | operator+ (const SparseVector< T > &L, const Vector< T > &R) |
|
SRI | operator+ (const SRI &Sleft, const SRI &Sright) |
|
Matrix< T > | operator+ (const T d, const ConstMatrixBase< T, BaseClass > &m) |
|
SparseVector< T > | operator+ (const Vector< T > &L, const SparseVector< T > &R) |
|
FileSpec::FileSpecType & | operator++ (FileSpec::FileSpecType &fst, int) |
|
Matrix< T > | operator- (const ConstMatrixBase< T, BaseClass > &m, const T d) |
|
Matrix< T > | operator- (const ConstMatrixBase< T, BaseClass1 > &l, const ConstMatrixBase< T, BaseClass2 > &r) |
|
SparseMatrix< T > | operator- (const Matrix< T > &L, const SparseMatrix< T > &R) |
|
Position | operator- (const Position &left, const Position &right) noexcept |
|
SparseMatrix< T > | operator- (const SparseMatrix< T > &L, const Matrix< T > &R) |
|
SparseMatrix< T > | operator- (const SparseMatrix< T > &L, const SparseMatrix< T > &R) |
|
SparseVector< T > | operator- (const SparseVector< T > &L, const SparseVector< T > &R) |
|
SparseVector< T > | operator- (const SparseVector< T > &L, const Vector< T > &R) |
|
Matrix< T > | operator- (const T d, const ConstMatrixBase< T, BaseClass > &m) |
|
SparseVector< T > | operator- (const Vector< T > &L, const SparseVector< T > &R) |
|
FileSpec::FileSpecType & | operator-- (FileSpec::FileSpecType &fst, int) |
|
Matrix< T > | operator/ (const ConstMatrixBase< T, BaseClass > &m, const T d) |
|
Matrix< T > | operator/ (const T d, const ConstMatrixBase< T, BaseClass > &m) |
|
bool | operator< (const IonexData::IonexValType &x, const IonexData::IonexValType &y) |
|
bool | operator< (const RinexObsType &x, const RinexObsType &y) |
|
std::ostream & | operator<< (FFStream &o, const FFData &f) |
|
ostream & | operator<< (ostream &os, const EarthOrientation &eo) |
|
ostream & | operator<< (ostream &os, const EOPPrediction &eopp) |
|
ostream & | operator<< (ostream &os, const format &f) |
|
ostream & | operator<< (ostream &os, const LabeledVector &LV) |
|
ostream & | operator<< (ostream &os, const Namelist &N) |
|
ostream & | operator<< (ostream &os, const SRI &S) |
|
ostream & | operator<< (ostream &os, const SRIleastSquares &srif) |
|
ostream & | operator<< (ostream &os, const TimeSystem ts) |
|
ostream & | operator<< (ostream &os, const WtdAveStats &was) |
|
ostream & | operator<< (ostream &s, CarrierBand cb) |
|
ostream & | operator<< (ostream &s, const BrcClockCorrection &eph) |
|
ostream & | operator<< (ostream &s, const BrcKeplerOrbit &eph) |
|
ostream & | operator<< (ostream &s, const EngEphemeris &eph) |
|
ostream & | operator<< (ostream &s, const Epoch &e) |
|
ostream & | operator<< (ostream &s, const Exception &e) |
|
ostream & | operator<< (ostream &s, const ExceptionLocation &e) |
|
ostream & | operator<< (ostream &s, const gnsstk::SatelliteSystem sys) |
|
ostream & | operator<< (ostream &s, const PackedNavBits &pnb) |
|
ostream & | operator<< (ostream &s, const Position &p) |
|
ostream & | operator<< (ostream &s, GLOCOrbitType e) |
|
ostream & | operator<< (ostream &s, GLOCRegime e) |
|
ostream & | operator<< (ostream &s, GLOCSatType e) |
|
ostream & | operator<< (ostream &s, GLOFNavPCode e) |
|
ostream & | operator<< (ostream &s, GLOFNavSatType e) |
|
ostream & | operator<< (ostream &s, GPSLNavL2Codes e) |
|
ostream & | operator<< (ostream &s, ObservationType ot) |
|
ostream & | operator<< (ostream &s, SVHealth h) |
|
ostream & | operator<< (ostream &s, TrackingCode tc) |
|
std::ostream & | operator<< (std::ostream &o, const CommonTime &ct) |
|
std::ostream & | operator<< (std::ostream &os, const gnsstk::Xvt &xvt) noexcept |
|
std::ostream & | operator<< (std::ostream &os, const LabeledMatrix &lm) |
|
std::ostream & | operator<< (std::ostream &os, const LabeledVector &lv) |
|
std::ostream & | operator<< (std::ostream &os, const SparseMatrix< T > &SM) |
|
std::ostream & | operator<< (std::ostream &os, const SparseVector< T > &SV) |
|
std::ostream & | operator<< (std::ostream &os, const TimeSystem ts) |
|
std::ostream & | operator<< (std::ostream &os, const Xvt::HealthStatus &health) noexcept |
|
std::ostream & | operator<< (std::ostream &os, IERSConvention cv) |
|
std::ostream & | operator<< (std::ostream &os, ReferenceFrame f) |
|
std::ostream & | operator<< (std::ostream &os, SatPass &sp) |
|
std::ostream & | operator<< (std::ostream &s, CarrierBand e) |
|
std::ostream & | operator<< (std::ostream &s, const AllanDeviation &a) |
|
std::ostream & | operator<< (std::ostream &s, const AlmOrbit &ao) |
|
std::ostream & | operator<< (std::ostream &s, const Angle &a) |
|
std::ostream & | operator<< (std::ostream &s, const AngleReduced &a) |
|
std::ostream & | operator<< (std::ostream &s, const BivarStats< T > &BVS) |
|
std::ostream & | operator<< (std::ostream &s, const CNavFilterData &nfd) |
|
std::ostream & | operator<< (std::ostream &s, const ConstMatrixBase< T, E > &a) |
|
std::ostream & | operator<< (std::ostream &s, const ConstVectorBase< T, E > &a) |
|
std::ostream & | operator<< (std::ostream &s, const EngAlmanac &alm) |
|
std::ostream & | operator<< (std::ostream &s, const Epoch &t) |
|
std::ostream & | operator<< (std::ostream &s, const FormattedDouble &d) |
|
std::ostream & | operator<< (std::ostream &s, const gnsstk::GPSZcount &z) |
|
std::ostream & | operator<< (std::ostream &s, const gnsstk::NavMessageTypeSet &nmts) |
|
std::ostream & | operator<< (std::ostream &s, const gnsstk::Triple &v) |
|
std::ostream & | operator<< (std::ostream &s, const gnsstk::WxObservation &obs) noexcept |
|
std::ostream & | operator<< (std::ostream &s, const GSatID &sat) |
|
std::ostream & | operator<< (std::ostream &s, const IonexData::IonexValType ivt) |
|
std::ostream & | operator<< (std::ostream &s, const LNavFilterData &nfd) |
|
std::ostream & | operator<< (std::ostream &s, const NavFilterKey &nfk) |
|
std::ostream & | operator<< (std::ostream &s, const NavID &p) |
|
std::ostream & | operator<< (std::ostream &s, const NavMessageID &nmid) |
|
std::ostream & | operator<< (std::ostream &s, const NavSatelliteID &nsid) |
|
std::ostream & | operator<< (std::ostream &s, const NavSignalID &nsid) |
|
std::ostream & | operator<< (std::ostream &s, const ObsEpoch &oe) noexcept |
|
std::ostream & | operator<< (std::ostream &s, const ObsID &p) |
|
std::ostream & | operator<< (std::ostream &s, const ObsRngDev &ord) noexcept |
|
std::ostream & | operator<< (std::ostream &s, const PackedNavBits &pnb) |
|
std::ostream & | operator<< (std::ostream &s, const RefFrame &rf) |
|
std::ostream & | operator<< (std::ostream &s, const Rinex3ObsHeader::Fields &v) |
|
std::ostream & | operator<< (std::ostream &s, const RinexObsType rot) |
|
std::ostream & | operator<< (std::ostream &s, const RinexSatID &sat) |
|
std::ostream & | operator<< (std::ostream &s, const SatelliteSystem sys) |
|
std::ostream & | operator<< (std::ostream &s, const SatID &p) |
|
std::ostream & | operator<< (std::ostream &s, const SatMetaData &smd) |
|
std::ostream & | operator<< (std::ostream &s, const SatMetaDataStore::SVNID &svn) |
|
std::ostream & | operator<< (std::ostream &s, const SatMetaDataStore::SystemBlock &sblk) |
|
std::ostream & | operator<< (std::ostream &s, const SeqStats< T > &ST) |
|
std::ostream & | operator<< (std::ostream &s, const SP3SatID &sat) |
|
std::ostream & | operator<< (std::ostream &s, const Stats< T > &ST) |
|
std::ostream & | operator<< (std::ostream &s, const SvObsEpoch &obs) noexcept |
|
std::ostream & | operator<< (std::ostream &s, const Transformer &t) |
|
std::ostream & | operator<< (std::ostream &s, const TwoSampleStats< T > &TSS) |
|
std::ostream & | operator<< (std::ostream &s, const ValidType< T > &r) noexcept |
|
std::ostream & | operator<< (std::ostream &s, const WtdStats< T > &ST) |
|
std::ostream & | operator<< (std::ostream &s, CorrectorType t) |
|
std::ostream & | operator<< (std::ostream &s, GLOFNavPCode e) |
|
std::ostream & | operator<< (std::ostream &s, GLOFNavSatType e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::AngleType e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::CorrDupHandling e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::GalDataValid e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::GalHealthStatus e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::GLOCOrbitType e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::GLOCRegime e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::GLOCSatType e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::GPSLNavL2Codes e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::IonexStoreStrategy e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::NavMessageType e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::NavType e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::NavValidityType e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::ObservationType e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::RefFrameRlz e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::RefFrameSys e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::SVHealth e) |
|
std::ostream & | operator<< (std::ostream &s, gnsstk::TrackingCode e) |
|
std::ostream & | operator<< (std::ostream &s, SatMetaData::ClockType ct) |
|
std::ostream & | operator<< (std::ostream &s, SatMetaData::Status status) |
|
std::ostream & | operator<< (std::ostream &s, XmitAnt e) |
|
bool | operator== (const IonexData::IonexValType &x, const IonexData::IonexValType &y) |
|
bool | operator== (const Namelist &N1, const Namelist &N2) |
|
bool | operator== (const RinexObsType &x, const RinexObsType &y) |
|
std::istream & | operator>> (FFStream &i, FFData &f) |
|
std::istream & | operator>> (std::istream &s, FormattedDouble &d) |
|
Namelist | operator^ (const Namelist &N1, const Namelist &N2) |
|
Namelist | operator| (const Namelist &N1, const Namelist &N2) |
|
Matrix< T > | operator|| (const ConstMatrixBase< T, BaseClass1 > &l, const ConstMatrixBase< T, BaseClass2 > &r) |
|
Matrix< T > | operator|| (const ConstMatrixBase< T, BaseClass1 > &l, const ConstVectorBase< T, BaseClass2 > &r) |
|
Matrix< T > | operator|| (const ConstVectorBase< T, BaseClass1 > &l, const ConstMatrixBase< T, BaseClass2 > &r) |
|
Matrix< T > | operator|| (const ConstVectorBase< T, BaseClass1 > &l, const ConstVectorBase< T, BaseClass2 > &r) |
|
SparseMatrix< T > | operator|| (const SparseMatrix< T > &L, const SparseMatrix< T > &R) |
|
SparseMatrix< T > | operator|| (const SparseMatrix< T > &L, const Vector< T > &V) |
|
Matrix< double > | orbitNormalAttitude (const Position &pos, const Position &vel) |
|
Matrix< T > | outer (const ConstVectorBase< T, BaseClass > &v, const ConstVectorBase< T, BaseClass > &w) |
|
std::string | printAs (const CommonTime &t, const std::string &fmt) |
|
std::string | printTime (const CommonTime &t, const std::string &fmt) |
|
void | QSort (T *sa, int na, int(*comp)(const T &, const T &)=gnsstk::Qsort_compare) |
|
void | QSort (T *sa, S *pa, int na, int(*comp)(const T &, const T &)=gnsstk::Qsort_compare) |
|
int | Qsort_compare (const T &a, const T &b) |
|
double | Rand (long seed=0) |
|
double | RandExpCor (double dt, double sigma, double T, double xlast) |
|
double | RandNorm (double sigma) |
|
double | RandomWalk (double dt, double sigma, double xlast) |
|
double | range (const Position &A, const Position &B) |
|
void | reallyGetRecordVer2 (Rinex3ObsStream &strm, Rinex3ObsData &rod) |
|
void | reallyPutRecordVer2 (Rinex3ObsStream &strm, const Rinex3ObsData &rod) |
|
int | RegisterARLUTExtendedTypes (void) |
|
int | RegisterExtendedRinexObsType (std::string t, std::string d=std::string("(undefined)"), std::string u=std::string("undefined"), unsigned int dep=0) |
|
int | RegisterExtendedRinexObsType (string t, string d, string u, unsigned int dep) |
|
double | RelativityCorrection (const Xvt &svPosVel) |
|
void | removeMilliseconds (std::vector< SatPass > &SPList, msecHandler &msh) |
|
void | removeMilliseconds (vector< SatPass > &SPList, msecHandler &msh) |
|
T | RMS (const ConstVectorBase< T, BaseClass > &l) |
|
Matrix< T > | rotation (T angle, int axis) |
|
double | Round (double x) |
|
T | RSS (const ConstVectorBase< T, BaseClass > &l) |
|
T | RSS (T aa, T bb) |
|
T | RSS (T aa, T bb, T cc) |
|
T | RSS (T aa, T bb, T cc, T dd) |
|
Matrix< double > | satelliteAttitude (const Position &sat, const Position &sun) |
|
double | satelliteEarthSunAngle (const Position &sat, const Position &sun) |
|
void | satelliteNadirAzimuthAngles (const Position &sv, const Position &rx, const Matrix< double > &rot, double &nadir, double &azimuth) |
|
double | satelliteYawAngle (const Position &pos, const Position &vel, const Position &sun, const bool &blkIIRF, double &yawrate) |
|
int | SatPassFromRinexFiles (std::vector< std::string > &filenames, std::vector< std::string > &obstypes, double dt, std::vector< SatPass > &SPList, std::vector< RinexSatID > exSats=std::vector< RinexSatID >(), bool lenient=true, gnsstk::Epoch beginTime=gnsstk::CommonTime::BEGINNING_OF_TIME, gnsstk::Epoch endTime=gnsstk::CommonTime::END_OF_TIME) |
|
int | SatPassFromRinexFiles (vector< string > &filenames, vector< string > &obstypes, double dtin, vector< SatPass > &SPList, vector< RinexSatID > exSats, bool lenient, Epoch beginTime, Epoch endTime) |
|
int | SatPassToRinex2File (const std::string &filename, RinexObsHeader &header, std::vector< SatPass > &SPList) |
|
int | SatPassToRinex2File (const string &filename, RinexObsHeader &header, vector< SatPass > &SPList) |
|
int | SatPassToRinex3File (const std::string &filename, const Rinex3ObsHeader &header, const std::map< char, std::vector< std::string >> &sysobs, std::vector< SatPass > &SPList) |
|
int | SatPassToRinex3File (const string &filename, const Rinex3ObsHeader &headerIn, const map< char, vector< string >> &sysobs, vector< SatPass > &SPList) |
|
void | scanTime (CommonTime &t, const std::string &str, const std::string &fmt) |
|
void | scanTime (CommonTime &t, const string &str, const string &fmt) |
|
void | scanTime (TimeTag &btime, const std::string &str, const std::string &fmt) |
|
void | scanTime (TimeTag &btime, const string &str, const string &fmt) |
|
double | seriesIncompGamma (double a, double x) |
|
double | shadowFactor (const Position &sv, const Position &sun) |
|
double | shadowFactor (double angRadEarth, double angRadSun, double angSeparation) |
|
static void | shortcut (ostream &os, const long HOW) |
|
T | SimpleLagrangeInterpolation (const std::vector< T > &X, const std::vector< T > &Y, const T x) |
|
T | slowDet (const ConstMatrixBase< T, BaseClass > &l) |
|
Position | solarPosition (const CommonTime &t, double &AR) |
|
double | solarPositionShadowFactor (double Rearth, double Rsun, double dES) |
|
std::string | sortRinex3ObsFiles (std::vector< std::string > &files) |
|
string | sortRinex3ObsFiles (vector< string > &files) |
|
std::string | sortRinexObsFiles (std::vector< std::string > &files) |
|
string | sortRinexObsFiles (vector< string > &files) |
|
SparseMatrix< T > | SparseHouseholder (const SparseMatrix< T > &A) |
|
void | SrifMU (Matrix< T > &R, Vector< T > &Z, const Matrix< T > &H, Vector< T > &D, unsigned int M=0) |
|
void | SrifMU (Matrix< T > &R, Vector< T > &Z, Matrix< T > &A, unsigned int M=0) |
|
void | SrifMU (Matrix< T > &R, Vector< T > &Z, SparseMatrix< T > &A, const unsigned int M) |
|
void | SrifMU (Matrix< T > &R, Vector< T > &Z, SparseMatrix< T > &P, Vector< T > &D, const unsigned int M) |
|
ListStats< bt > | stats (const std::list< bt > &lst) |
|
double | StudentsCDF (double t, int n) |
|
double | StudentsPDF (double X, int n) |
|
T | sum (const ConstVectorBase< T, BaseClass > &l) |
|
void | sunOrbitAngles (const Position &pos, const Position &vel, const Position &sun, double &beta, double &phi) |
|
long | timeAdjust8BitWeekRollover (long toCorrectWeek, long &refWeek) |
|
long | timeAdjustWeekRollover (long toCorrectWeek, long &refWeek) |
|
static void | timeDisplay (ostream &os, const CommonTime &t) |
|
gnsstk::Xvt::HealthStatus | toXvtHealth (SVHealth e) |
|
T | trace (const ConstMatrixBase< T, BaseClass > &m) |
|
SparseMatrix< T > | transform (const SparseMatrix< T > &M, const SparseMatrix< T > &C) |
|
Vector< T > | transformDiag (const SparseMatrix< T > &P, const Matrix< T > &C) |
|
Matrix< T > | transpose (const ConstMatrixBase< T, BaseClass > &m) |
|
SparseMatrix< T > | transpose (const SparseMatrix< T > &M) |
|
SparseMatrix< T > | transposeTimesMatrix (const SparseMatrix< T > &M) |
|
std::string | typeString () |
|
Matrix< T > | UDU (const Matrix< T > &A, Vector< T > &D) |
|
Matrix< double > | upEastNorth (Position &pos, bool geocentric) |
|
Matrix< double > | upEastNorthGeocentric (Position &pos) |
|
Matrix< double > | upEastNorthGeodetic (Position &pos) |
|
Matrix< T > | upperCholesky (const Matrix< T > &A, const T ztol=T(1.e-16)) |
|
SparseMatrix< T > | upperCholesky (const SparseMatrix< T > &A) |
|
double | ura2accuracy (short ura) noexcept |
|
double | ura2CNAVaccuracy (short ura) |
|
double | ura2CNAVNominalaccuracy (short ura) |
|
double | ura2nominalAccuracy (short ura) noexcept |
|
Matrix< T > | UTtimesTranspose (const Matrix< T > &UT) |
|
std::vector< T > | vec_intersect (const std::vector< T > &v1, const std::vector< T > &v2) |
|
std::vector< T > | vec_notintersect (const std::vector< T > &v1, const std::vector< T > &v2) |
|
VecBaseNewBinaryOperator Vector Vector< T > Vector< T > VecBaseNewBinaryOperator Vector VecBaseNewBinaryOperator Vector Vector< bool > Vector< bool > | VecBaseNewBinaryOperator (!=, Vector< bool >) VecBaseNewBinaryOperator(< |
|
VecBaseNewBinaryOperator Vector Vector< T > | VecBaseNewBinaryOperator (+, Vector< T >) VecBaseNewBinaryOperator(- |
|
VecBaseNewBinaryOperator Vector | VecBaseNewBinaryOperator (/, Vector< T >) VecBaseNewBinaryOperator(% |
|
VecBaseNewBinaryOperator Vector Vector< T > Vector< T > VecBaseNewBinaryOperator Vector VecBaseNewBinaryOperator Vector Vector< bool > | VecBaseNewBinaryOperator (<, Vector< bool >) VecBaseNewBinaryOperator(> |
|
VecBaseNewBinaryOperator Vector Vector< T > Vector< T > VecBaseNewBinaryOperator Vector VecBaseNewBinaryOperator Vector Vector< bool > Vector< bool > Vector< bool > | VecBaseNewBinaryOperator (>=, Vector< bool >) template< class T |
|
VecBaseNewBinaryOperator Vector Vector< T > Vector< T > VecBaseNewBinaryOperator Vector VecBaseNewBinaryOperator Vector | VecBaseNewBinaryOperator (|, Vector< T >) VecBaseNewBinaryOperator( |
|
| VecShortwireComparisonOperator (eq,==) VecShortwireComparisonOperator(ne |
|
int | vectorindex (const std::vector< T > &vec, const T &value) |
|
bool | willPrintAs (const std::string &fmt) |
|