SolarSystem.hpp
Go to the documentation of this file.
1 //==============================================================================
2 //
3 // This file is part of GNSSTk, the ARL:UT GNSS Toolkit.
4 //
5 // The GNSSTk is free software; you can redistribute it and/or modify
6 // it under the terms of the GNU Lesser General Public License as published
7 // by the Free Software Foundation; either version 3.0 of the License, or
8 // any later version.
9 //
10 // The GNSSTk is distributed in the hope that it will be useful,
11 // but WITHOUT ANY WARRANTY; without even the implied warranty of
12 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 // GNU Lesser General Public License for more details.
14 //
15 // You should have received a copy of the GNU Lesser General Public
16 // License along with GNSSTk; if not, write to the Free Software Foundation,
17 // Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110, USA
18 //
19 // This software was developed by Applied Research Laboratories at the
20 // University of Texas at Austin.
21 // Copyright 2004-2022, The Board of Regents of The University of Texas System
22 //
23 //==============================================================================
24 
25 //==============================================================================
26 //
27 // This software was developed by Applied Research Laboratories at the
28 // University of Texas at Austin, under contract to an agency or agencies
29 // within the U.S. Department of Defense. The U.S. Government retains all
30 // rights to use, duplicate, distribute, disclose, or release this software.
31 //
32 // Pursuant to DoD Directive 523024
33 //
34 // DISTRIBUTION STATEMENT A: This software has been approved for public
35 // release, distribution is unlimited.
36 //
37 //==============================================================================
38 
69 //------------------------------------------------------------------------------------
70 #ifndef SOLAR_SYSTEM_INCLUDE
71 #define SOLAR_SYSTEM_INCLUDE
72 
73 //------------------------------------------------------------------------------------
74 // includes
75 // system
76 #include <fstream>
77 #include <iostream>
78 #include <map>
79 #include <string>
80 #include <vector>
81 
82 // GNSSTk
83 #include "EphTime.hpp"
84 #include "Exception.hpp"
85 #include "Position.hpp"
86 
87 // geomatics
88 #include "EOPStore.hpp"
89 #include "EarthOrientation.hpp"
90 #include "IERSConvention.hpp"
91 #include "SolarSystemEphemeris.hpp"
92 #include "SolidEarthTides.hpp"
93 #include "SunEarthSatGeometry.hpp"
94 #include "logstream.hpp"
95 
96 namespace gnsstk
97 {
98 
99  //---------------------------------------------------------------------------------
163  {
164 
165  public:
172  {
173  iersconv = inputiers;
174  }
175 
180  void setConvention(const IERSConvention& conv)
181  {
182  iersconv = conv;
184  }
185 
188 
197  int initializeWithBinaryFile(std::string filename)
198  {
200 
201  // if not defined, set IERS convention to the default; otherwise test it.
203  {
204  if (EphNumber() == 403)
205  {
207  }
208  else if (EphNumber() == 405)
209  {
210  iersconv = IERSConvention::IERS2010; // the default
211  }
212  else
213  {
214  LOG(ERROR) << "Unknown ephemeris number " << EphNumber();
215  }
216  }
217  else
218  {
220  }
221 
222  return iret;
223  }
224 
229  {
230  EphTime t;
233  return static_cast<CommonTime>(t);
234  }
235 
240  {
241  EphTime t;
244  return static_cast<CommonTime>(t);
245  }
246 
250  EarthOrientation getEOP(double mjdutc)
251  {
252  return EOPStore::getEOP(mjdutc, iersconv);
253  }
254 
264  const EphTime& tt);
265 
277  const EphTime& tt, Position& Pos, Position& Vel);
278 
286  {
287  try
288  {
290  }
291  catch (Exception& e)
292  {
293  GNSSTK_RETHROW(e);
294  }
295  }
296 
304  {
305  try
306  {
308  }
309  catch (Exception& e)
310  {
311  GNSSTK_RETHROW(e);
312  }
313  }
314 
322  void solarPositionVelocity(const EphTime& tt, Position& Pos, Position& Vel)
323  {
324  try
325  {
327  Vel);
328  }
329  catch (Exception& e)
330  {
331  GNSSTK_RETHROW(e);
332  }
333  }
334 
342  void lunarPositionVelocity(const EphTime& tt, Position& Pos, Position& Vel)
343  {
344  try
345  {
347  Vel);
348  }
349  catch (Exception& e)
350  {
351  GNSSTK_RETHROW(e);
352  }
353  }
354 
374  {
375  try
376  {
378  return gnsstk::satelliteAttitude(SV, Sun);
379  }
380  catch (Exception& e)
381  {
382  GNSSTK_RETHROW(e);
383  }
384  }
385 
405  void sunOrbitAngles(const EphTime& tt, const Position& Pos,
406  const Position& Vel, double& beta, double& phi)
407  {
408  try
409  {
411  gnsstk::sunOrbitAngles(Pos, Vel, Sun, beta, phi);
412  }
413  catch (Exception& e)
414  {
415  GNSSTK_RETHROW(e);
416  }
417  }
418 
437  {
438  try
439  {
440  const Position Sun = SolarSystem::solarPosition(tt);
441  const Position Moon = SolarSystem::lunarPosition(tt);
442  const double EMRAT = SolarSystem::ratioEarthToMoonMass();
443  const double SERAT = SolarSystem::ratioSunToEarthMass();
444  return gnsstk::computeSolidEarthTides(site, tt, Sun, Moon, EMRAT,
445  SERAT, iersconv);
446  }
447  catch (Exception& e)
448  {
449  GNSSTK_RETHROW(e);
450  }
451  }
452 
464  Triple computePolarTides(const Position site, const EphTime& tt)
465  {
466  try
467  {
468  EphTime ttag(tt);
470  const EarthOrientation eo = EOPStore::getEOP(ttag.dMJD(), iersconv);
471  return gnsstk::computePolarTides(site, tt, eo.xp, eo.yp, iersconv);
472  }
473  catch (Exception& e)
474  {
475  GNSSTK_RETHROW(e);
476  }
477  }
478 
479  private:
489 
492  const int ephno)
493  {
494  if (ephno == -1)
495  {
496  return; // no ephemeris (yet)
497  }
498 
499  if ((ephno == 403 && conv != IERSConvention::IERS1996) ||
500  (ephno == 405 && conv != IERSConvention::IERS2003 &&
501  conv != IERSConvention::IERS2010))
502  {
503 
504  LOG(WARNING) << "Warning - IERS convention (" << conv
505  << ") is inconsistent with SolarSystemEphemeris ("
506  << ephno << ")";
507  }
508  }
509 
510  }; // end class SolarSystem
511 
512 } // end namespace gnsstk
513 
514 #endif // SOLAR_SYSTEM_INCLUDE
515 // nothing below this
gnsstk::EphTime::convertSystemTo
void convertSystemTo(const TimeSystem &ts)
Definition: EphTime.hpp:96
gnsstk::SolarSystemEphemeris::endTimeMJD
double endTimeMJD() const
Return the MJD of end time of the data (system TDB)
Definition: SolarSystemEphemeris.hpp:342
gnsstk::SolarSystem::endTime
CommonTime endTime() const
Definition: SolarSystem.hpp:239
gnsstk::SolarSystemEphemeris::initializeWithBinaryFile
int initializeWithBinaryFile(const std::string &filename)
Definition: SolarSystemEphemeris.cpp:874
SolidEarthTides.hpp
EphTime.hpp
gnsstk::SolarSystem::startTime
CommonTime startTime() const
Definition: SolarSystem.hpp:228
SunEarthSatGeometry.hpp
gnsstk::EphTime::setTimeSystem
void setTimeSystem(TimeSystem sys)
Definition: EphTime.hpp:141
gnsstk::computePolarTides
Triple computePolarTides(const Position &site, const EphTime &ttag, double xp, double yp, const IERSConvention &iers)
Definition: SolidEarthTides.cpp:711
gnsstk::SolarSystem::getConvention
IERSConvention getConvention() const
get the IERS Convention
Definition: SolarSystem.hpp:187
logstream.hpp
gnsstk::SolarSystem::testIERSvsEphemeris
void testIERSvsEphemeris(const IERSConvention conv, const int ephno)
Helper routine to keep the tests in one place.
Definition: SolarSystem.hpp:491
Position.hpp
gnsstk::SolarSystem::sunOrbitAngles
void sunOrbitAngles(const EphTime &tt, const Position &Pos, const Position &Vel, double &beta, double &phi)
Definition: SolarSystem.hpp:405
gnsstk::IERSConvention::IERS1996
@ IERS1996
gnsstk::WARNING
@ WARNING
Definition: logstream.hpp:57
gnsstk::Triple
Definition: Triple.hpp:68
gnsstk::SolarSystem::iersconv
IERSConvention iersconv
Definition: SolarSystem.hpp:488
gnsstk::SolarSystem::lunarPositionVelocity
void lunarPositionVelocity(const EphTime &tt, Position &Pos, Position &Vel)
Definition: SolarSystem.hpp:342
gnsstk
For Sinex::InputHistory.
Definition: BasicFramework.cpp:50
gnsstk::EOPStore
Definition: EOPStore.hpp:69
gnsstk::EOPStore::getEOP
EarthOrientation getEOP(double mjd, const IERSConvention &conv)
Definition: EOPStore.cpp:313
gnsstk::SolarSystemEphemeris::EphNumber
int EphNumber() const
Definition: SolarSystemEphemeris.hpp:303
gnsstk::EarthOrientation::yp
double yp
Polar motion angle yp, in arcseconds.
Definition: EarthOrientation.hpp:100
gnsstk::SolarSystem::initializeWithBinaryFile
int initializeWithBinaryFile(std::string filename)
Definition: SolarSystem.hpp:197
gnsstk::Exception
Definition: Exception.hpp:151
gnsstk::TimeSystem::TDB
@ TDB
Barycentric dynamical time (JPL ephemeris); very near TT.
gnsstk::SolarSystem::computeSolidEarthTides
Triple computeSolidEarthTides(const Position site, const EphTime &tt)
Definition: SolarSystem.hpp:436
SolarSystemEphemeris.hpp
gnsstk::SolarSystem::solarPositionVelocity
void solarPositionVelocity(const EphTime &tt, Position &Pos, Position &Vel)
Definition: SolarSystem.hpp:322
gnsstk::SolarSystem::solarPosition
Position solarPosition(const EphTime &tt)
Definition: SolarSystem.hpp:285
gnsstk::SolarSystemEphemeris::Planet
Planet
These are indexes used by the caller of inertialPositionVelocity().
Definition: SolarSystemEphemeris.hpp:110
gnsstk::satelliteAttitude
Matrix< double > satelliteAttitude(const Position &sat, const Position &sun)
Definition: SunEarthSatGeometry.cpp:266
gnsstk::Matrix< double >
gnsstk::ERROR
@ ERROR
Definition: logstream.hpp:57
gnsstk::CommonTime
Definition: CommonTime.hpp:84
gnsstk::EphTime
Definition: EphTime.hpp:67
gnsstk::SolarSystem::ECEFPosition
Position ECEFPosition(const SolarSystemEphemeris::Planet body, const EphTime &tt)
Definition: SolarSystem.cpp:79
gnsstk::SolarSystemEphemeris
Definition: SolarSystemEphemeris.hpp:96
gnsstk::SolarSystemEphemeris::idMoon
@ idMoon
10 Moon (Geocentric coordinates)
Definition: SolarSystemEphemeris.hpp:124
gnsstk::SolarSystem::SolarSystem
SolarSystem(IERSConvention inputiers=IERSConvention::Unknown)
Definition: SolarSystem.hpp:171
gnsstk::beta
double beta(double x, double y)
Definition: SpecialFuncs.cpp:204
EOPStore.hpp
gnsstk::IERSConvention
IERSConvention
Definition: IERSConvention.hpp:69
gnsstk::SolarSystemEphemeris::ratioEarthToMoonMass
double ratioEarthToMoonMass()
Return the Earth-to-Moon mass ratio.
Definition: SolarSystemEphemeris.hpp:324
GNSSTK_RETHROW
#define GNSSTK_RETHROW(exc)
Definition: Exception.hpp:369
gnsstk::IERSConvention::Unknown
@ Unknown
gnsstk::IERSConvention::IERS2003
@ IERS2003
gnsstk::TimeSystem::UTC
@ UTC
Coordinated Universal Time (e.g., from NTP)
gnsstk::SolarSystemEphemeris::startTimeMJD
double startTimeMJD() const
Return the MJD of start time of the data (system TDB)
Definition: SolarSystemEphemeris.hpp:339
IERSConvention.hpp
LOG
#define LOG(level)
define the macro that is used to write to the log stream
Definition: logstream.hpp:315
gnsstk::IERSConvention::IERS2010
@ IERS2010
Exception.hpp
gnsstk::sunOrbitAngles
void sunOrbitAngles(const Position &pos, const Position &vel, const Position &sun, double &beta, double &phi)
Definition: SunEarthSatGeometry.cpp:465
EarthOrientation.hpp
gnsstk::SolarSystem::computePolarTides
Triple computePolarTides(const Position site, const EphTime &tt)
Definition: SolarSystem.hpp:464
gnsstk::SolarSystemEphemeris::idSun
@ idSun
11 Sun
Definition: SolarSystemEphemeris.hpp:125
gnsstk::SolarSystem::setConvention
void setConvention(const IERSConvention &conv)
Definition: SolarSystem.hpp:180
gnsstk::SolarSystem::getEOP
EarthOrientation getEOP(double mjdutc)
Definition: SolarSystem.hpp:250
gnsstk::SolarSystem::ECEFPositionVelocity
void ECEFPositionVelocity(const SolarSystemEphemeris::Planet body, const EphTime &tt, Position &Pos, Position &Vel)
Definition: SolarSystem.cpp:102
gnsstk::SolarSystemEphemeris::ratioSunToEarthMass
double ratioSunToEarthMass()
Return the Sun-to-Earth mass ratio.
Definition: SolarSystemEphemeris.hpp:330
gnsstk::Position
Definition: Position.hpp:136
gnsstk::computeSolidEarthTides
Triple computeSolidEarthTides(const Position &site, const EphTime &ttag, const Position &Sun, const Position &Moon, double EMRAT, double SERAT, const IERSConvention &iers)
Definition: SolidEarthTides.cpp:80
gnsstk::EphTime::dMJD
double dMJD() const
Definition: EphTime.hpp:171
gnsstk::SolarSystem::satelliteAttitude
Matrix< double > satelliteAttitude(const EphTime &tt, const Position &SV)
Definition: SolarSystem.hpp:373
gnsstk::EarthOrientation
Definition: EarthOrientation.hpp:93
gnsstk::EphTime::setMJD
void setMJD(long double mjd)
Definition: EphTime.hpp:155
gnsstk::SolarSystem
Definition: SolarSystem.hpp:162
gnsstk::EarthOrientation::xp
double xp
Polar motion angle xp, in arcseconds.
Definition: EarthOrientation.hpp:97
gnsstk::SolarSystem::lunarPosition
Position lunarPosition(const EphTime &tt)
Definition: SolarSystem.hpp:303


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