class EarthOrientation encapsulates the Earth orientation parameters or EOPs, which consist of the polar motion angle xp and yp and the time offset UT1-UTC. These three parameters are determined by interpolating measured values managed by class EOPStore. Also, this class includes several static functions that implement the models in the IERS Conventions (1996, 2003 or 2010), many of which involve the EOPs. This includes the frame transformation between the conventional terrestrial (i.e. ECEF) frame and the conventional celestial (inertial) frame. The class implements models of precession and nutation of Earth's axis, as well as the precise rotation of Earth and its 'wobble' as given by the EOPs. The class requires time to be in one of two systems: UTC or TT; class EphTime is a simple class that enforces this requirement (plus TDB), transformation to and from CommonTime should be automatic. (TT is terrestrial and TDB is barycentric dynamic time, which is the time of SolarSystemEphemeris.) Also cf. classes EOPStore and SolarSystem. References: IERS1996: IERS Technical Note 21, "IERS Conventions (1996)," Dennis D. McCarthy, U.S. Naval Observatory, 1996. IERS2003: IERS Technical Note 32, "IERS Conventions (2003)," Dennis D. McCarthy and Gerard Petit eds., U.S. Naval Observatory and Bureau International des Poids et Mesures, 2004. IERS2010: IERS Technical Note 36, "IERS Conventions (2010)," Gerard Petit and Brian Luzum eds., Bureau International des Poids et Mesures and U.S. Naval Observatory, 2010.
Definition at line 93 of file EarthOrientation.hpp.
#include <EarthOrientation.hpp>
Public Member Functions | |
EarthOrientation () | |
Constructor. More... | |
Matrix< double > | ECEFtoInertial (const EphTime &t, bool reduced=false) |
Matrix< double > | ECEFtoJ2000 (const EphTime &t, bool reduced=false) |
double | GAST (const EphTime &t, bool reduced=false) |
double | GMST (const EphTime &t, bool reduced=false) |
void | interpolateEOP (const EphTime &ttag, const std::vector< double > &time, const std::vector< double > &X, const std::vector< double > &Y, std::vector< double > &dT, const IERSConvention &conv) |
Matrix< double > | nutationMatrix (const EphTime &t) |
double | obliquity (double T) |
Matrix< double > | polarMotionMatrix (const EphTime &t) |
Matrix< double > | precessionMatrix (const EphTime &t) |
Matrix< double > | preciseEarthRotation (const EphTime &t) |
Static Public Member Functions | |
static double | coordTransTime (EphTime t) |
static double | D (double T) |
static double | F (double T) |
static double | L (double T) |
static double | LE (double T) |
static double | LJ (double T) |
static double | LMa (double T) |
static double | LMe (double T) |
static double | LN (double T) |
static double | Lp (double T) |
static double | LS (double T) |
static double | LU (double T) |
static double | LV (double T) |
static double | Omega (double T) |
static double | Omega2003 (double T) |
static double | Pa (double T) |
Public Attributes | |
IERSConvention | convention |
IERS convention appropriate for this data. More... | |
double | UT1mUTC |
Time offset UT1 minus UTC, in seconds. More... | |
double | xp |
Polar motion angle xp, in arcseconds. More... | |
double | yp |
Polar motion angle yp, in arcseconds. More... | |
Static Public Attributes | |
static const double | ARCSEC_PER_CIRCLE = 1296000.0 |
how many arcseconds in 360 degrees? More... | |
static const double | ARCSEC_TO_RAD = 4.848136811095359935899141e-6 |
convert arc seconds to radians More... | |
static const double | DEG_TO_RAD = 0.0174532925199432957692369 |
convert degrees to radians and back More... | |
static const double | HALFPI = (TWOPI / 4.) |
static const int | intJulianEpoch = 51544 |
static const double | JulianEpoch = 51544.5 |
static const double | PI = (TWOPI / 2.) |
pi, 2*pi and pi/2 More... | |
static const double | RAD_TO_DEG = 57.29577951308232087679815 |
static const double | TWOPI = 6.283185307179586476925287 |
Private Member Functions | |
Matrix< double > | ECEFtoInertial1996 (EphTime t, double xp, double yp, double UT1mUTC, bool reduced=false) |
Matrix< double > | ECEFtoInertial2003 (EphTime t, double xp, double yp, double UT1mUTC) |
Matrix< double > | ECEFtoInertial2010 (EphTime t, double xp, double yp, double UT1mUTC) |
Static Private Member Functions | |
static Matrix< double > | biasMatrix2010 () |
static double | EarthRotationAngle (const EphTime &t, double &UT1mUTC) |
static double | equationOfEquinoxes2003 (EphTime t) |
static Matrix< double > | FukushimaWilliams (double gamb, double phib, double psib, double epsa) |
static void | FukushimaWilliams (double T, double &gamb, double &phib, double &psib, double &eps) |
static double | gast1996 (EphTime t, double om, double eps, double dpsi, double UT1mUTC) |
static double | GAST1996 (EphTime t, double UT1mUTC, bool reduced=false) |
static double | GAST2003 (EphTime t, double UT1mUTC) |
static double | GAST2010 (EphTime t, double UT1mUTC) |
static double | GMST1996 (EphTime t, double UT1mUTC, bool reduced=false) |
static double | GMST2003 (EphTime t, double UT1mUTC) |
static double | GMST2010 (EphTime t, double UT1mUTC) |
static void | nutationAngles1996 (double T, double &deps, double &dpsi, double &om) |
static void | nutationAngles2003 (double T, double &deps, double &dpsi) |
static void | nutationAngles2010 (double T, double &deps, double &dpsi) |
static Matrix< double > | nutationMatrix (double eps, double dpsi, double deps) |
static Matrix< double > | nutationMatrix1996 (double T) |
static Matrix< double > | nutationMatrix2003 (double T) |
static Matrix< double > | nutationMatrix2010 (double T) |
static double | obliquity1996 (double T) |
static double | obliquity2010 (double T) |
static Matrix< double > | polarMotionMatrix1996 (double xp, double yp) |
static Matrix< double > | polarMotionMatrix2003 (EphTime t, double xp, double yp) |
static Matrix< double > | precessionMatrix1996 (double T) |
static Matrix< double > | precessionMatrix2003 (double T) |
static Matrix< double > | precessionMatrix2010 (double T) |
static void | precessionRateCorrections2003 (double T, double &dpsi, double &deps) |
static Matrix< double > | preciseEarthRotation2003 (double T) |
static Matrix< double > | preciseEarthRotation2010 (double T) |
static double | S (double T, double &X, double &Y, IERSConvention which=IERSConvention::IERS2003) |
static double | Sprime (double T) |
static double | Sprime (EphTime t) |
Sprime with EphTime input; cf. Sprime(double T == coordTransTime(t)) More... | |
static void | UT1mUTCTidalCorrections (double T, double &UT1mUTR, double &dlodR, double &domegaR) |
static void | XYCIO (double &T, double &X, double &Y) |
Friends | |
std::ostream & | operator<< (std::ostream &s, const EarthOrientation &) |
append to output stream More... | |
|
inline |
Constructor.
Definition at line 109 of file EarthOrientation.hpp.
|
staticprivate |
IERS2010 frame bias matrix, a 3x3 rotation matrix; cf. FukushimaWilliams().
Definition at line 2764 of file EarthOrientation.cpp.
|
static |
'coordinate transformation time', which is used throughout the class, defined as the terrestrial time (TT) since J2000, in centuries. Valid for IERS1996, IERS2003, IERS2010
t | EphTime time of interest. |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 805 of file EarthOrientation.cpp.
|
static |
mean elongation of the moon from the sun, in radians, given T, the coordTransTime at the time of interest. Valid for IERS1996, IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 874 of file EarthOrientation.cpp.
|
staticprivate |
Starting with 2003 conventions a new method for computing the transformation fron ITRS to GCRS is provided by the Celestial Ephemeris Origin (CEO) which is based on the Earth Rotation Angle, which depends on time(UT1). Ref. IERS Tech Note 32 Chap 5 Eqn 14
t | EphTime time of interest |
UT1mUTC | offset UT1-UTC |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 1719 of file EarthOrientation.cpp.
Matrix< double > gnsstk::EarthOrientation::ECEFtoInertial | ( | const EphTime & | t, |
bool | reduced = false |
||
) |
Generate the full transformation matrix (3x3 rotation) relating the ECEF frame to the conventional inertial frame. Input is the time of interest; use this object's EOPs - the polar motion angles xp and yp (arcseconds), and UT1-UTC (seconds) (xp,yp and UT1-UTC are as found in the IERS bulletin).
t | epoch of the rotation. |
reduced | true when UT1mUTC is 'reduced', meaning assumes 'no tides', as is the case with the NGA EOPs (default=F). |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Exception | if convention is not defined |
Definition at line 1247 of file EarthOrientation.cpp.
|
private |
Generate the full transformation matrix (3x3 rotation) relating the ECEF frame to the conventional inertial frame, using IERS 1996 conventions. Input is the time of interest, the polar motion angles xp and yp (arcsecs), and UT1-UTC (sec) (xp,yp and UT1-UTC are just as found in the IERS bulletin)
t | EphTime epoch of the rotation. |
xp | Earth wobble in arcseconds, as found in the IERS bulletin. |
yp | Earth wobble in arcseconds, as found in the IERS bulletin. |
UT1mUTC | UT1-UTC in seconds, as found in the IERS bulletin. |
reduced | bool true when UT1mUTC is 'reduced', meaning assumes 'no tides', as is the case with the NGA EOPs (default=F). |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 2854 of file EarthOrientation.cpp.
|
private |
Generate the full transformation matrix (3x3 rotation) relating the ECEF frame to the conventional inertial frame, using IERS 2003 conventions. Input is the time of interest, the polar motion angles xp and yp (arcsecs), and UT1-UTC (sec) (xp,yp and UT1-UTC are just as found in the IERS bulletin)
t | EphTime epoch of the rotation. |
xp | Earth wobble in arcseconds, as found in the IERS bulletin. |
yp | Earth wobble in arcseconds, as found in the IERS bulletin. |
UT1mUTC | UT1-UTC in seconds, as found in the IERS bulletin. |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 2925 of file EarthOrientation.cpp.
|
private |
Generate the full transformation matrix (3x3 rotation) relating the ECEF frame to the conventional inertial frame, using IERS 2010 conventions. Input is the time of interest, the polar motion angles xp and yp (arcsecs), and UT1-UTC (sec) (xp,yp and UT1-UTC are just as found in the IERS bulletin)
t | EphTime epoch of the rotation. |
xp | Earth wobble in arcseconds, as found in the IERS bulletin. |
yp | Earth wobble in arcseconds, as found in the IERS bulletin. |
UT1mUTC | UT1-UTC in seconds, as found in the IERS bulletin. |
Exception | if TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 3002 of file EarthOrientation.cpp.
Compute the transformation from ECEF to the J2000 dynamical (inertial) frame. This differs from the ECEFtoInertial transformation only by the frame bias matrix. Only available in IERS2010. NB currently not tested. ***
Exception |
|
staticprivate |
Equation of the equinoxes complementary terms, IAU 2000 (IERS 2003) Note that GAST = GMST + equationOfEquinoxes
t | EphTime epoch of interest |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 1770 of file EarthOrientation.cpp.
|
static |
mean longitude of the moon minus Omega, in radians, given T, the coordTransTime at the time of interest. Valid for IERS1996, IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 860 of file EarthOrientation.cpp.
|
staticprivate |
For IERS 2010, generate any of B = frame bias matrix PB = Precession*Bias matrix NPB = Nutation*Precession*Bias matrix given the four F-W angles with caviats, as follows. Get B by passing the full F-W angles at J2000. Get PB by passing the full F-W angles at time time of interest. Get NPB by passing the full F-W angles at time time of interest with nutation angle corrections (nutationAngles2010()). Specifically, FukushimaWilliams(T, gamb, phib, psib, eps); nutationAngles2010(T, deps, dpsi); NPB = FukushimaWilliams(gamb, phib, psib+dpsi, eps+deps); Thus the precession matrix is computed as PB * transpose(B), and the nutation matrix is computed as N = NPB * transpose(PB).
gamb | F-W angle |
phib | F-W angle |
psib | F-W angle |
epsa | F-W angle, the obliquity |
Definition at line 2355 of file EarthOrientation.cpp.
|
staticprivate |
Compute Fukushima-Williams angles for computing nutation, frame bias and precession matrices in IERS2010; cf. FukushimaWilliams(). NB. fourth angle is obliquity.
Definition at line 2305 of file EarthOrientation.cpp.
Compute Greenwich Apparent Sidereal Time, or the Greenwich hour angle of the true vernal equinox (radians), given the coordinate time of interest, and this object's UT1-UTC (sec), which comes from the IERS bulletin.
t | epoch of the rotation. |
reduced | true when UT1mUTC is 'reduced', meaning assumes 'no tides', as is the case with the NGA EOPs (default=F). |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Exception | if convention is not defined |
Definition at line 1078 of file EarthOrientation.cpp.
|
staticprivate |
Helper to compute the Greenwich hour angle of the true vernal equinox, or Greenwich Apparent Sidereal Time, in radians, for IERS1996, given the (UT) time of interest t, and, where T = coordTransTime(t), om = Omega(T) = mean longitude of lunar ascending node, in radians, ep = obliquity(T) = the obliquity of the ecliptic, in radians, dp = nutation in longitude (counted in the ecliptic), in seconds of arc.
GAST = Greenwich hour angle of the true vernal equinox = Greenwich apparent sidereal time = GMST + dpsi*cos(eps) + 0.00264"*sin(Omega) + 0.000063"*sin(2*Omega) (these terms account for the accumulated precession and nutation in right ascension and minimize any discontinuity in UT1)
GMST = Greenwich hour angle of the mean vernal equinox = Greenwich mean sidereal time = GMST0 + r*[UTC + (UT1-UTC)] r = is the ratio of universal to sidereal time = 1.002737909350795 + 5.9006E-11*T' - 5.9e-15*T'^2 T' = days'/36525 days'= number of days elapsed since t0 = +/-(integer+0.5) and (UT1-UTC) (seconds) is taken from the IERS bulletin
GMST0 = GMST at 0h UT1 = 6h 41m (50.54841+8640184.812866*T'+0.093104*T'^2-6.2E-6*T'^3)s
t | EphTime time of interest. |
om | Omega(T), mean longitude of lunar ascending node, in radians, |
eps | obliquity(T), the obliquity of the ecliptic, in radians, |
dpsi | nutation in longitude (counted in the ecliptic), in seconds of arc |
UT1mUTC | UT1-UTC in seconds, as found in the IERS bulletin. |
Exception |
Definition at line 2089 of file EarthOrientation.cpp.
|
staticprivate |
Compute Greenwich Apparent Sidereal Time, or the Greenwich hour angle of the true vernal equinox (radians), given the coordinate time of interest, and UT1-UTC (sec), which comes from the IERS bulletin.
t | EphTime epoch of the rotation. |
UT1mUTC | UT1-UTC in seconds, as found in the IERS bulletin. |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 2142 of file EarthOrientation.cpp.
|
staticprivate |
Compute Greenwich Apparent Sidereal Time, or the Greenwich hour angle of the true vernal equinox (radians), given the coordinate time of interest, and UT1-UTC (sec), which comes from the IERS bulletin.
t | EphTime epoch of the rotation. |
UT1mUTC | UT1-UTC in seconds, as found in the IERS bulletin. |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 2178 of file EarthOrientation.cpp.
|
staticprivate |
Compute Greenwich Apparent Sidereal Time, or the Greenwich hour angle of the true vernal equinox (radians), given the coordinate time of interest, and UT1-UTC (sec), which comes from the IERS bulletin.
t | EphTime epoch of the rotation |
UT1mUTC | UT1-UTC in seconds, as found in the IERS bulletin |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 2218 of file EarthOrientation.cpp.
Compute Greenwich Mean Sidereal Time, or the Greenwich hour angle of the mean vernal equinox (radians), given the coordinate time of interest, using this->UT1mUTC (sec), which comes from the IERS bulletin.
t | epoch of the rotation. |
reduced | true when UT1mUTC is 'reduced', meaning assumes 'no tides', as is the case with the NGA EOPs (default=F). |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Exception | if convention is not defined |
Definition at line 1042 of file EarthOrientation.cpp.
|
staticprivate |
Compute Greenwich Mean Sidereal Time, or the Greenwich hour angle of the mean vernal equinox (radians), given the coordinate time of interest, and UT1-UTC (sec), which comes from the IERS bulletin. For IERS1996,03
t | EphTime epoch of the rotation. |
UT1mUTC | UT1-UTC in seconds, as found in the IERS bulletin. |
reduced | true when UT1mUTC is 'reduced', meaning assumes 'no tides', as is the case with the NGA EOPs (default=F). |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 1960 of file EarthOrientation.cpp.
|
staticprivate |
Compute Greenwich Mean Sidereal Time, or the Greenwich hour angle of the mean vernal equinox (radians), given the coordinate time of interest, and UT1-UTC (sec), which comes from the IERS bulletin. For IERS2003
t | EphTime epoch of the rotation. |
UT1mUTC | UT1-UTC in seconds, as found in the IERS bulletin. |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 2025 of file EarthOrientation.cpp.
|
staticprivate |
Compute Greenwich Mean Sidereal Time, or the Greenwich hour angle of the mean vernal equinox (radians), given the coordinate time of interest, and UT1-UTC (sec), which comes from the IERS bulletin. For IERS2010
t | EphTime epoch of the rotation. |
UT1mUTC | UT1-UTC in seconds, as found in the IERS bulletin. |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 2054 of file EarthOrientation.cpp.
void gnsstk::EarthOrientation::interpolateEOP | ( | const EphTime & | ttag, |
const std::vector< double > & | time, | ||
const std::vector< double > & | X, | ||
const std::vector< double > & | Y, | ||
std::vector< double > & | dT, | ||
const IERSConvention & | conv | ||
) |
Given parallel arrays of length four containing the values from EOPStore for time (int MJD) and EOPs xp, yp, and UT1mUTC, where the time of interest ttag lies within the values of the time array, interpolate and apply corrections to determine the EOPs at ttag, using the algorithm prescribed by the given IERS convention.
ttag | EphTime at which to compute EOPs |
time | vector of length 4 of consecutive MJDs from EOPStore; ttag must lie within this timespan. |
X | vector of length 4 of consecutive xp from EOPStore. |
Y | vector of length 4 of consecutive yp from EOPStore. |
dT | vector of length 4 of consecutive UT1mUTC from EOPStore. |
conv | the IERSConvention to be used. |
InvalidRequest |
Definition at line 158 of file EarthOrientation.cpp.
|
static |
mean anomaly of the moon, in radians, given T, the coordTransTime at the time of interest. Valid for IERS1996, IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 888 of file EarthOrientation.cpp.
|
static |
mean longitude of Earth, in radians, given T, the coordTransTime at the time of interest. Valid for IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 937 of file EarthOrientation.cpp.
|
static |
mean longitude of Jupiter, in radians, given T, the coordTransTime at the time of interest. Valid for IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 958 of file EarthOrientation.cpp.
|
static |
mean longitude of Mars, in radians, given T, the coordTransTime at the time of interest. Valid for IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 947 of file EarthOrientation.cpp.
|
static |
mean longitude of Mercury, in radians, given T, the coordTransTime at the time of interest. Valid for IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 917 of file EarthOrientation.cpp.
|
static |
mean longitude of Neptune, in radians, given T, the coordTransTime at the time of interest. Valid for IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 991 of file EarthOrientation.cpp.
|
static |
mean anomaly of the sun, in radians, given T, the coordTransTime at the time of interest. Valid for IERS1996, IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 901 of file EarthOrientation.cpp.
|
static |
mean longitude of Saturn, in radians, given T, the coordTransTime at the time of interest. Valid for IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 969 of file EarthOrientation.cpp.
|
static |
mean longitude of Uranus, in radians, given T, the coordTransTime at the time of interest. Valid for IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 980 of file EarthOrientation.cpp.
|
static |
mean longitude of Venus, in radians, given T, the coordTransTime at the time of interest. Valid for IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 927 of file EarthOrientation.cpp.
|
staticprivate |
Nutation of the obliquity (deps) and of the longitude (dpsi), IERS 1996 model (ref pg 26), given
T | the coordinate transformation time at the time of interest |
deps | nutation of the obliquity (output) in radians |
dpsi | nutation of the longitude (output) in radians |
om | longitude mean ascending node of lunar orbit, from mean equinox |
Definition at line 2372 of file EarthOrientation.cpp.
|
staticprivate |
Nutation of the obliquity (deps) and of the longitude (dpsi), IERS 2003
T | the coordinate transformation time at the time of interest |
deps | nutation of the obliquity (output) in radians |
dpsi | nutation of the longitude (output) in radians |
Definition at line 2447 of file EarthOrientation.cpp.
|
staticprivate |
Nutation of the obliquity (deps) and of the longitude (dpsi), IERS 2010
T | the coordinate transformation time at the time of interest |
deps | nutation of the obliquity (output) in radians |
dpsi | nutation of the longitude (output) in radians |
Definition at line 2572 of file EarthOrientation.cpp.
Generate an Earth Nutation Matrix (3X3 rotation) at the given EphTime.
t | EphTime epoch of the rotation. |
Exception | if convention is not defined |
Definition at line 1184 of file EarthOrientation.cpp.
|
staticprivate |
nutation matrix, a 3x3 rotation matrix, given
eps | obliquity(T), the obliquity of the ecliptic, in radians, |
dpsi | the nutation in longitude (counted in the ecliptic) in radians. |
deps | the nutation in obliquity, in radians. |
Definition at line 2586 of file EarthOrientation.cpp.
|
staticprivate |
IERS1996 nutation matrix, a 3x3 rotation matrix, given
T | the coordinate transformation time at the time of interest |
Definition at line 2599 of file EarthOrientation.cpp.
|
staticprivate |
IERS2003 nutation matrix, a 3x3 rotation matrix (including the frame bias matrix), given
T | the coordinate transformation time at the time of interest |
Definition at line 2612 of file EarthOrientation.cpp.
|
staticprivate |
IERS2010 nutation matrix, a 3x3 rotation matrix, given
T | the coordinate transformation time at the time of interest; cf. FukushimaWilliams(). |
Definition at line 2630 of file EarthOrientation.cpp.
double gnsstk::EarthOrientation::obliquity | ( | double | T | ) |
obliquity of the ecliptic, in radians, given T, the coordTransTime at the time of interest. Valid for IERS1996 IERS2003 IERS2010
T | coordinate transformation time. |
Exception | if convention is not defined |
Definition at line 1013 of file EarthOrientation.cpp.
|
staticprivate |
obliquity of the ecliptic, in radians, given T, the coordTransTime at the time of interest, for IERS1996 (also 03)
T | coordinate transformation time. |
Definition at line 1923 of file EarthOrientation.cpp.
|
staticprivate |
obliquity of the ecliptic, in radians, given T, the coordTransTime at the time of interest, for IERS2010
T | coordinate transformation time. |
Definition at line 1938 of file EarthOrientation.cpp.
|
static |
mean longitude of lunar ascending node, in radians, given T, the coordTransTime at the time of interest. Valid for IERS1996, IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 832 of file EarthOrientation.cpp.
|
static |
mean longitude of lunar ascending node, in radians, given T, the coordTransTime at the Epoch of interest. valid for IERS 2003, 2010
T | coordinate transformation time. |
Definition at line 846 of file EarthOrientation.cpp.
|
static |
general precession in longitude, in radians, given T, the coordTransTime at the time of interest. Valid for IERS2003, IERS2010
T | coordinate transformation time. |
Definition at line 1003 of file EarthOrientation.cpp.
Generate transformation matrix (3X3 rotation) due to this object's EOPs polar motion angles xp and yp (arcseconds), as found in the IERS bulletin;
t | EphTime epoch of the rotation. |
Exception | if convention is not defined |
Definition at line 1111 of file EarthOrientation.cpp.
|
staticprivate |
Generate transformation matrix (3X3 rotation) due to the polar motion angles xp and yp (arcseconds), as found in the IERS bulletin;
xp | Earth wobble in arcseconds, as found in the IERS bulletin. |
yp | Earth wobble in arcseconds, as found in the IERS bulletin. |
Definition at line 2266 of file EarthOrientation.cpp.
|
staticprivate |
Generate transformation matrix (3X3 rotation) due to the polar motion angles xp and yp (arcseconds), as found in the IERS bulletin; The returned matrix R transforms the CIP into TRS: V(TRS) = R * V(CIP). see sofa pom00. Also valid for IERS2010.
t | EphTime epoch of the rotation. |
xp | Earth wobble in arcseconds, as found in the IERS bulletin. |
yp | Earth wobble in arcseconds, as found in the IERS bulletin. |
Definition at line 2286 of file EarthOrientation.cpp.
Generate an Earth Precession Matrix (3X3 rotation) at the given EphTime.
t | EphTime epoch of the rotation. |
Exception | if convention is not defined |
Definition at line 1136 of file EarthOrientation.cpp.
|
staticprivate |
IERS1996 precession matrix, a 3x3 rotation matrix, given
T | the coordinate transformation time at the time of interest |
Definition at line 2659 of file EarthOrientation.cpp.
|
staticprivate |
IERS2003 precession matrix, a 3x3 rotation matrix (including the frame bias matrix), given
T | the coordinate transformation time at the time of interest |
Definition at line 2681 of file EarthOrientation.cpp.
|
staticprivate |
IERS2010 precession matrix, a 3x3 rotation matrix, given
T | the coordinate transformation time at the time of interest Does not include the frame bias matrix; cf. FukushimaWilliams(). |
Definition at line 2779 of file EarthOrientation.cpp.
|
staticprivate |
IERS2003 precession and obliquity rate corrections, IAU 2000
T | the coordinate transformation time at the time of interest |
Definition at line 2752 of file EarthOrientation.cpp.
Generate precise transformation matrix (3X3 rotation) for Earth motion due to precession, nutation and frame bias, at the given time of interest.
t | EphTime epoch of the rotation. |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Exception | if convention is not defined |
Definition at line 1220 of file EarthOrientation.cpp.
|
staticprivate |
Generate precise transformation matrix (3X3 rotation) for Earth motion due to precession, nutation and frame bias, at the given time of interest. Valid only for 2010
T | coordTransTime(EphTime t) for time of interest |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 2801 of file EarthOrientation.cpp.
|
staticprivate |
Generate precise transformation matrix (3X3 rotation) for Earth motion due to precession, nutation and frame bias, at the given time of interest. Valid only for 2010
T | coordTransTime(EphTime t) for time of interest |
Exception | if the TimeSystem conversion fails (if TimeSystem is Unknown) |
Definition at line 2826 of file EarthOrientation.cpp.
|
staticprivate |
locator s which gives the position of the CIO on the equator of the CIP, given the coordinate transformation time T and the coordinates X,Y of the CIP. Consistent with IAU 2000A (IERS2003) precession-nutation, and P03 precession (IERS2010). Derived in part from SOFA routine s00.c for IERS2003 and s06.c for IERS2010. Used for both IERS2003 and IERS2010, but not for IERS1996
T | the coordinate transformation time at the time of interest |
X | the X coordinate of the CIP (input) |
Y | the Y coordinate of the CIP (input) |
which | the IERS convention to be used (input) |
Definition at line 1327 of file EarthOrientation.cpp.
|
staticprivate |
The position of the Terrestrial Ephemeris Origin (TEO) on the equator of the Celestial Intermediate Pole (CIP), as given by the quantity s'. Also called the Terrestrial Intermediate Origin (TIO). Ref. IERS Tech Note 32 Chap 5 Eqn 12
T | Coordinate transformation time T. |
Definition at line 1587 of file EarthOrientation.cpp.
|
inlinestaticprivate |
Sprime with EphTime input; cf. Sprime(double T == coordTransTime(t))
Definition at line 471 of file EarthOrientation.hpp.
|
staticprivate |
Zonal tide terms for corrections of UT1mUTC when that quantity does not include tides (e.g. NGA EOP), ref. IERS 1996 Ch. 8, table 8.1 pg 74.
T | the coordinate transformation time at the time of interest |
UT1mUTR | the correction to UT1mUTC (seconds) |
dlodR | the correction to the length of day (seconds) |
domegaR | the correction to the Earth rotation rate, rad/second. |
Definition at line 1903 of file EarthOrientation.cpp.
|
staticprivate |
coordinates X,Y of the Celestial Intermediate Origin (CIO) using a series based on IAU 2006 precession and IAU 2000A nutation (IERS 2010). The coordinates form a unit vector that points towards the CIO; they include the effects of frame bias, precession and nutation. cf. sofa xy06
T | the coordinate transformation time at the time of interest |
X | x coordinate of CIO |
Y | y coordinate of CIO |
Definition at line 1601 of file EarthOrientation.cpp.
|
friend |
append to output stream
|
static |
how many arcseconds in 360 degrees?
Definition at line 143 of file EarthOrientation.hpp.
|
static |
convert arc seconds to radians
Definition at line 140 of file EarthOrientation.hpp.
IERSConvention gnsstk::EarthOrientation::convention |
IERS convention appropriate for this data.
Definition at line 106 of file EarthOrientation.hpp.
|
static |
convert degrees to radians and back
Definition at line 137 of file EarthOrientation.hpp.
Definition at line 134 of file EarthOrientation.hpp.
|
static |
integer MJD J2000 epoch for use in maximizing precision of coordTransTime()
Definition at line 131 of file EarthOrientation.hpp.
|
static |
Epoch for the coordinate transformation time, used throughout the formulas = J2000 = January 1 2000 12h UT but use MJD for this constant
Definition at line 125 of file EarthOrientation.hpp.
pi, 2*pi and pi/2
Definition at line 134 of file EarthOrientation.hpp.
|
static |
Definition at line 137 of file EarthOrientation.hpp.
|
static |
Definition at line 134 of file EarthOrientation.hpp.
double gnsstk::EarthOrientation::UT1mUTC |
Time offset UT1 minus UTC, in seconds.
Definition at line 103 of file EarthOrientation.hpp.
double gnsstk::EarthOrientation::xp |
Polar motion angle xp, in arcseconds.
Definition at line 97 of file EarthOrientation.hpp.
double gnsstk::EarthOrientation::yp |
Polar motion angle yp, in arcseconds.
Definition at line 100 of file EarthOrientation.hpp.