Public Member Functions | Private Member Functions | Private Attributes | List of all members
gnsstk::SolarSystem Class Reference

Detailed Description

Class SolarSystem provides the functionality of SolarSytemEphemeris in the Earth-centered Earth-fixed (ECEF) frame, and makes use of this to implement models for solid Earth tides (SETs) as well as geometry-related functions involving satellite, Sun, Moon and Earth, e.g. satellite attitude.

The class publicly inherits two large classes: class SolarSystemEphemeris (the JPL solar system ephemeris) and class EOPStore (storage and retrieval of Earth orientiation parameters). The motivation for this design is that the fundamental routine of the ephemeris, SolarSystem::ECEFPositionVelocity(planet,time), always requires simultaneous EarthOrientiation data, and this class enforces that requirement. This design allows the class to retrieve EOPs and with them implement the transformation from the inertial (celestial) frame of the solar system ephemeris to the ECEF (terrestrial) frame (using class EarthOrientation).

The class must first be initialized by initializing both SolarSystemEphemeris and EOPStore. SolarSystemEphemeris is initialized by calling initializeWithBinaryFile(filename), passing the name of a SolarSystem binary file (cf. the convertSSEph app that read JPL ASCII files and creates a binary file). EOPStore is initialized by calling addIERSFile(filename), passing it the finals2000A.data or similar file obtained, e.g. from USNO; see EOPStore. The IERS convention (1996, 2003 or 2010) may be set at this time; is also included in the class, it is required by EarthOrientation but must be consistent with the SolarSystemEphemeris.

Class design:
                 SolarSystem
  • calls with EphTime (limits to UTC,TT,TDB only)
  • member IERSconvention - keeps SSEph and EO consistent
  • has all the functionality of the inherited classes, plus, for convenience, SolidEarthTides, poleTides, / Sun-Earth-Sat (SunEarthSat.hpp) geometry functions / (all using the high-accuracy SolarSystemEphemeris) / \ / (inherits) \ / \ SolarSystemEphemeris: EOPStore:
from JPL data (-> binary file)   - load 'IERS' files e.g. USNO finals.data
  • times: MJD(TDB) only - times: MJD(UTC) only
  • Planets+Sun+Moon position(t) - simple store of <MJD, EarthOrientation> o o o o o (uses) o o o o o EarthOrientation:
    • EOP = (polar motion x,y + UT1-UTC)
    • calls with EphTime (using UTC,TT only)
    • many static functions implementing IERS conventions (1996, 2003, 2010); e.g. Precession, Nutation, GMST, Terrestrial <=> Inertial frame transformations.

Definition at line 162 of file SolarSystem.hpp.

#include <SolarSystem.hpp>

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

Public Member Functions

Triple computePolarTides (const Position site, const EphTime &tt)
 
Triple computeSolidEarthTides (const Position site, const EphTime &tt)
 
Position ECEFPosition (const SolarSystemEphemeris::Planet body, const EphTime &tt)
 
void ECEFPositionVelocity (const SolarSystemEphemeris::Planet body, const EphTime &tt, Position &Pos, Position &Vel)
 
CommonTime endTime () const
 
IERSConvention getConvention () const
 get the IERS Convention More...
 
EarthOrientation getEOP (double mjdutc)
 
int initializeWithBinaryFile (std::string filename)
 
Position lunarPosition (const EphTime &tt)
 
void lunarPositionVelocity (const EphTime &tt, Position &Pos, Position &Vel)
 
Matrix< double > satelliteAttitude (const EphTime &tt, const Position &SV)
 
void setConvention (const IERSConvention &conv)
 
Position solarPosition (const EphTime &tt)
 
void solarPositionVelocity (const EphTime &tt, Position &Pos, Position &Vel)
 
 SolarSystem (IERSConvention inputiers=IERSConvention::Unknown)
 
CommonTime startTime () const
 
void sunOrbitAngles (const EphTime &tt, const Position &Pos, const Position &Vel, double &beta, double &phi)
 
- Public Member Functions inherited from gnsstk::SolarSystemEphemeris
double AU ()
 
void clearStorage ()
 
double endTimeMJD () const
 Return the MJD of end time of the data (system TDB) More...
 
int EphNumber () const
 
double getConstant (const std::string &name)
 
int initializeWithBinaryFile (const std::string &filename)
 
double ratioEarthToMoonMass ()
 Return the Earth-to-Moon mass ratio. More...
 
double ratioSunToEarthMass ()
 Return the Sun-to-Earth mass ratio. More...
 
int readASCIIdata (const std::string &filename)
 
int readASCIIdata (std::vector< std::string > &filenames)
 
void readASCIIheader (const std::string &filename)
 
int readBinaryFile (const std::string &filename)
 
void relativeInertialPositionVelocity (double MJD, Planet target, Planet center, double PV[6], bool kilometers=true)
 
 SolarSystemEphemeris ()
 
double startTimeMJD () const
 Return the MJD of start time of the data (system TDB) More...
 
int writeASCIIdata (std::ostream &os)
 
int writeASCIIheader (std::ostream &os)
 
int writeBinaryFile (const std::string &filename)
 
- Public Member Functions inherited from gnsstk::EOPStore
void addEOP (int MJD, EarthOrientation &eop)
 Add to the store directly. More...
 
int addEOP (int MJD, EOPPrediction &eopp)
 
void addEOPPFile (const std::string &filename)
 
void addFile (const std::string &filename)
 
void addIERSFile (const std::string &filename)
 
void clear ()
 clear the store More...
 
void dump (short detail=0, std::ostream &s=std::cout) const
 
void edit (int mjdmin, int mjdmax)
 
 EOPStore ()
 Constructor. More...
 
EarthOrientation getEOP (double mjd, const IERSConvention &conv)
 
int getFirstTimeMJD ()
 Return first time (MJD) in the store. More...
 
int getLastTimeMJD ()
 Return last time (MJD) in the store. More...
 
int size ()
 return the number of entries in the store More...
 

Private Member Functions

void testIERSvsEphemeris (const IERSConvention conv, const int ephno)
 Helper routine to keep the tests in one place. More...
 

Private Attributes

IERSConvention iersconv
 

Additional Inherited Members

- Public Types inherited from gnsstk::SolarSystemEphemeris
enum  Planet {
  idNone = 0, idMercury, idVenus, idEarth,
  idMars, idJupiter, idSaturn, idUranus,
  idNeptune, idPluto, idMoon, idSun,
  idSolarSystemBarycenter, idEarthMoonBarycenter, idNutations, idLibrations
}
 These are indexes used by the caller of inertialPositionVelocity(). More...
 
enum  ReturnValue {
  retOK = 0, retEarly = -1, retLate = -2, retStrm = -3,
  retEphN = -4
}
 Return values. More...
 

Constructor & Destructor Documentation

◆ SolarSystem()

gnsstk::SolarSystem::SolarSystem ( IERSConvention  inputiers = IERSConvention::Unknown)
inline

Empty and only constructor. The IERS convention should be consistent with the SolarSystemEphemeris file when initializeWithBinaryFile() is called, otherwise a warning is issued.

Definition at line 171 of file SolarSystem.hpp.

Member Function Documentation

◆ computePolarTides()

Triple gnsstk::SolarSystem::computePolarTides ( const Position  site,
const EphTime tt 
)
inline

Compute the site displacement due to rotational deformation due to polar motion for the given Position (assumed to fixed to the solid Earth) at the given time. Return a Triple containing the site displacement in ECEF XYZ coordinates with units meters. Reference IERS Conventions (1996) found in IERS Technical Note 21, ch. 7 pg 67.

Parameters
siteNominal position of the site of interest.
ttTime of interest.
Returns
Displacement vector, ECEF XYZ meters.
Exceptions
Exception

Definition at line 464 of file SolarSystem.hpp.

◆ computeSolidEarthTides()

Triple gnsstk::SolarSystem::computeSolidEarthTides ( const Position  site,
const EphTime tt 
)
inline

Compute the site displacement due to solid Earth tides for the given Position (assumed to be fixed to the solid Earth) at the given time, given the position of the site of interest; cf. gnsstk::computeSolidEarthTides(). Return a Triple containing the site displacement in ECEF XYZ coordinates with units meters. Reference IERS Conventions (1996) found in IERS Technical Note 21 and IERS Conventions (2003) found in IERS Technical Note 32 and IERS Conventions (2010) found in IERS Technical Note 36. NB. Currently only the largest terms are implemented, yielding a result accurate to the millimeter level. Specifically, TN21 pg 61 eq 8 and TN21 pg 65 eq 17.

Parameters
sitePosition Nominal position of the site of interest.
ttEphTime Time of interest.
Returns
Triple Displacement vector, ECEF XYZ in meters.
Exceptions
Exception

Definition at line 436 of file SolarSystem.hpp.

◆ ECEFPosition()

Position gnsstk::SolarSystem::ECEFPosition ( const SolarSystemEphemeris::Planet  body,
const EphTime tt 
)

Return the ECEF (terrestrial frame, relative to Earth's center) position of a Solar System body at the input time, with units meters.

Parameters
bodySolarSystemEphemeris::Planet of interest (input)
ttTime of interest (input)
Returns
ECEF Position of the body in meters.
Exceptions
Exception

Definition at line 79 of file SolarSystem.cpp.

◆ ECEFPositionVelocity()

void gnsstk::SolarSystem::ECEFPositionVelocity ( const SolarSystemEphemeris::Planet  body,
const EphTime tt,
Position Pos,
Position Vel 
)

Return the ECEF (terrestrial frame, relative to Earth's center) position and velocity of a Solar System body at the input time, with units meters and m/s.

Parameters
bodySolarSystemEphemeris::Planet of interest (input)
ttTime of interest (input)
PosPosition containing result for position in m in XYZ
VelPosition containing result for velocity in m/s in XYZ
Exceptions
Exception

Definition at line 102 of file SolarSystem.cpp.

◆ endTime()

CommonTime gnsstk::SolarSystem::endTime ( ) const
inline

Return the end time of the Solar System ephemeris data

Exceptions
Exception

Definition at line 239 of file SolarSystem.hpp.

◆ getConvention()

IERSConvention gnsstk::SolarSystem::getConvention ( ) const
inline

get the IERS Convention

Definition at line 187 of file SolarSystem.hpp.

◆ getEOP()

EarthOrientation gnsstk::SolarSystem::getEOP ( double  mjdutc)
inline

Overload EOPStore::getEOP() to use the IERS convention of this object

Exceptions
InvalidRequest

Definition at line 250 of file SolarSystem.hpp.

◆ initializeWithBinaryFile()

int gnsstk::SolarSystem::initializeWithBinaryFile ( std::string  filename)
inline

Overloaded function to load ephemeris file. A check of the ephemeris number and the IERS convention for this object is made; if the IERS convention is inconsistent with the ephemeris file then a warning is issued. Cf. SolarSystemEphemeris::initializeWithBinaryFile(std::string filename).

Exceptions
Exception

Definition at line 197 of file SolarSystem.hpp.

◆ lunarPosition()

Position gnsstk::SolarSystem::lunarPosition ( const EphTime tt)
inline

Convenience routine to get the ECEF position of the Moon

Parameters
ttTime of interest (input)
Returns
ECEF Position of the Moon in meters.
Exceptions
Exception

Definition at line 303 of file SolarSystem.hpp.

◆ lunarPositionVelocity()

void gnsstk::SolarSystem::lunarPositionVelocity ( const EphTime tt,
Position Pos,
Position Vel 
)
inline

Convenience routine to get the ECEF position and velocity of the Moon

Parameters
ttTime of interest (input)
PosPosition containing result for Lunar position in m in XYZ
VelPosition containing result for Lunar velocity in m/s in XYZ
Exceptions
Exception

Definition at line 342 of file SolarSystem.hpp.

◆ satelliteAttitude()

Matrix<double> gnsstk::SolarSystem::satelliteAttitude ( const EphTime tt,
const Position SV 
)
inline

Compute the satellite attitude, given the time and the satellite position SV Return a 3x3 Matrix which contains, as rows, the unit (ECEF) vectors X,Y,Z in the body frame of the satellite, namely Z = along the boresight (i.e. towards Earth center), Y = perpendicular to both Z and the satellite-sun direction, and X = completing the orthonormal triad. X will generally point toward the sun. Thus this rotation matrix R transforms an ECEF XYZ vector into the body frame of the satellite, so R * [ECEF XYZ Vector] = components in body frame. Also, R.transpose() * [satellite body frame Vector] = ECEF XYZ components. Also return the shadow factor, which is the fraction of the sun's area not visible to satellite; thus sf > 0 means the satellite is in eclipse.

Parameters
SVPosition Satellite position
Returns
Matrix<double>(3,3) Rotation matrix from XYZ to Satellite body frame.
Exceptions
Exception

Definition at line 373 of file SolarSystem.hpp.

◆ setConvention()

void gnsstk::SolarSystem::setConvention ( const IERSConvention conv)
inline

Choose an IERS Convention. If the input IERS convention is inconsistent with the loaded ephemeris then a warning is issued.

Definition at line 180 of file SolarSystem.hpp.

◆ solarPosition()

Position gnsstk::SolarSystem::solarPosition ( const EphTime tt)
inline

Convenience routine to get the ECEF position of the Sun

Parameters
ttTime of interest (input)
Returns
ECEF Position of the Sun in meters.
Exceptions
Exception

Definition at line 285 of file SolarSystem.hpp.

◆ solarPositionVelocity()

void gnsstk::SolarSystem::solarPositionVelocity ( const EphTime tt,
Position Pos,
Position Vel 
)
inline

Convenience routine to get the ECEF position and velocity of the Sun

Parameters
ttTime of interest (input)
PosPosition containing result for Solar position in m in XYZ
VelPosition containing result for Solar velocity in m/s in XYZ
Exceptions
Exception

Definition at line 322 of file SolarSystem.hpp.

◆ startTime()

CommonTime gnsstk::SolarSystem::startTime ( ) const
inline

Return the start time of the Solar System ephemeris data

Exceptions
Exception

Definition at line 228 of file SolarSystem.hpp.

◆ sunOrbitAngles()

void gnsstk::SolarSystem::sunOrbitAngles ( const EphTime tt,
const Position Pos,
const Position Vel,
double &  beta,
double &  phi 
)
inline

Compute the angle between the Sun and the plane of the orbit of the satellite, given the time and the satellite position and velocity at that time. Return the angle in radians; it lies between +-pi/2 and has the sign of RxV. That is, the angle is positive if the Sun is out of the orbit plane in the direction of R cross V; then Sun "sees" the orbit motion as counter-clockwise. Also return, in phi, the angle, in the plane of the orbit, from the Sun to the satellite; this lies between 0 and 2pi and increases in the direction of Vel.

Parameters
ttEphTime Time of interest
PosPosition Satellite position at tt
VelPosition Satellite velocity at tt (Cartesian, m/s)
phidouble Return angle in orbit plane, midnight to sat (radians)
betadouble Return angle sun to plane of satellite orbit (radians)
Note
NB. phi, beta and sesa, the satellite-earth-sun angle, form a right spherical triangle with sesa opposite the right angle. Thus cos(sesa)=cos(beta)*cos(phi).
Exceptions
Exception

Definition at line 405 of file SolarSystem.hpp.

◆ testIERSvsEphemeris()

void gnsstk::SolarSystem::testIERSvsEphemeris ( const IERSConvention  conv,
const int  ephno 
)
inlineprivate

Helper routine to keep the tests in one place.

Definition at line 491 of file SolarSystem.hpp.

Member Data Documentation

◆ iersconv

IERSConvention gnsstk::SolarSystem::iersconv
private

IERS convention in use with this instance of the class. This is determined either by reading the SolarSystemEphemeris number (403 -> IERS1996, 405 -> IERS2003 or IERS2010, the default), or by assignments; however if the IERS convention is inconsistent with the ephemeris then a warning will be issued at the reading of the ephemeris file or when the assignment is made.

Definition at line 488 of file SolarSystem.hpp.


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


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