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

Detailed Description

Compute the corrected range from receiver at position Rx, to the GPS satellite given by SatID sat, as well as azimuth, elevation, etc., given a nominal timetag (either received or transmitted time) and a NavLibrary.

The corrected range is a combination of the raw range (geometric range) minus SV clock offsets. The raw range can be written as:

\[ \rho_{rx}^{sv} = \biggl|\biggl|\mathbf{R}\bigl(-(t_r - t_t)\bigl)\cdot\mathbf{r}^{sv}(t_t) - \mathbf{r}^{rx}(t_r)\biggl|\biggl| \]

where,

$\mathbf{R}(\cdot)$ = ECEF frame rotation over a given time interval
$\mathbf{r}^{sv}(t_t)$ = ECEF position of SV at time of signal transmission ( $t_t$)
$\mathbf{r}^{rx}(t_r)$ = ECEF position of RX at time of signal receive ( $t_r$)

The different methods in this class represent different methodologies for solving the above equation depending on the available input. See each method for the background in solving for geometric range.

Definition at line 84 of file EphemerisRange.hpp.

#include <EphemerisRange.hpp>

Public Member Functions

double ComputeAtReceiveTime (const CommonTime &trNom, const Position &rx, const SatID sat, NavLibrary &navLib, NavSearchOrder order=NavSearchOrder::User, SVHealth xmitHealth=SVHealth::Any, NavValidityType valid=NavValidityType::ValidOnly, const EllipsoidModel &ellipsoid=GPSEllipsoid())
 
double ComputeAtTransmitSvTime (const CommonTime &ttNom, const double &pr, const Position &rx, const SatID sat, NavLibrary &navLib, NavSearchOrder order=NavSearchOrder::User, SVHealth xmitHealth=SVHealth::Any, NavValidityType valid=NavValidityType::ValidOnly, const EllipsoidModel &ellipsoid=GPSEllipsoid())
 
double ComputeAtTransmitTime (const CommonTime &trNom, const double &pr, const Position &rx, const SatID sat, NavLibrary &navLib, NavSearchOrder order=NavSearchOrder::User, SVHealth xmitHealth=SVHealth::Any, NavValidityType valid=NavValidityType::ValidOnly, const EllipsoidModel &ellipsoid=GPSEllipsoid())
 
double ComputeAtTransmitTime (const CommonTime &trNom, const Position &rx, const SatID sat, NavLibrary &navLib, NavSearchOrder order=NavSearchOrder::User, SVHealth xmitHealth=SVHealth::Any, NavValidityType valid=NavValidityType::ValidOnly, const EllipsoidModel &ellipsoid=GPSEllipsoid())
 
 CorrectedEphemerisRange ()
 Default constructor. More...
 

Public Attributes

double azimuth
 
double azimuthGeodetic
 
Triple cosines
 
double elevation
 
double elevationGeodetic
 
vshort health
 
vshort iodc
 The IODC of the GPS LNAV ephemeris, invalid for other GNSSes. More...
 
double rawrange
 The computed raw (geometric) range in meters. More...
 
double relativity
 The relativity correction in meters. More...
 
double svclkbias
 The satellite clock bias in meters. More...
 
double svclkdrift
 The satellite clock drift in m/s. More...
 
Xvt svPosVel
 The satellite position (m) and velocity (m/s) in ECEF coordinates. More...
 
CommonTime transmit
 The computed transmit time of the signal. More...
 

Private Member Functions

void updateCER (const Position &rx)
 

Constructor & Destructor Documentation

◆ CorrectedEphemerisRange()

gnsstk::CorrectedEphemerisRange::CorrectedEphemerisRange ( )
inline

Default constructor.

Definition at line 88 of file EphemerisRange.hpp.

Member Function Documentation

◆ ComputeAtReceiveTime()

double gnsstk::CorrectedEphemerisRange::ComputeAtReceiveTime ( const CommonTime trNom,
const Position rx,
const SatID  sat,
NavLibrary navLib,
NavSearchOrder  order = NavSearchOrder::User,
SVHealth  xmitHealth = SVHealth::Any,
NavValidityType  valid = NavValidityType::ValidOnly,
const EllipsoidModel ellipsoid = GPSEllipsoid() 
)

Compute the corrected range at RECEIVE time (receiver time frame), from rx to sat at trNom.

Note
This does not account for a RX clock bias that might be present in trNom. If a RX clock bias is known, adjust the input timestamp accordingly before calling this method.

This method uses an iterative solution solving for the geometric range and the time of flight. An initial guess is used for the time of flight, a geometric range is computed, and a new time of flight is computed with the relationship of $\tau = \frac{\rho_{rx}^{sv}}{c}$

Parameters
[in]trNomNominal receive time ( $\widetilde{t}_r^{rx}$).
[in]rxReceiver position ( $\mathbf{r}^{sv}(t_t)$).
[in]satSatellite ID to get the position for.
[in]navLibThe navigation data library to use for looking up satellite XVT.
[in]orderSpecify whether to search by receiver behavior or by nearest to when in time.
[in]xmitHealthThe desired health status of the satellite transmitting the nav data.
[in]validSpecify whether to search only for valid or invalid messages, or both.
[in]ellipsoidEllipsoid model to provide an ECEF rotation rate.
Returns
The corrected range from rx to sat at trNom.

Definition at line 65 of file EphemerisRange.cpp.

◆ ComputeAtTransmitSvTime()

double gnsstk::CorrectedEphemerisRange::ComputeAtTransmitSvTime ( const CommonTime ttNom,
const double &  pr,
const Position rx,
const SatID  sat,
NavLibrary navLib,
NavSearchOrder  order = NavSearchOrder::User,
SVHealth  xmitHealth = SVHealth::Any,
NavValidityType  valid = NavValidityType::ValidOnly,
const EllipsoidModel ellipsoid = GPSEllipsoid() 
)

Compute the corrected range at TRANSMIT time (SV time frame), from rx to sat at ttNom.

A similar methodology to ComputeAtTransmitTime but uses the SV's nominal transmit time and a pseudorange to estimate the receive time then geometric range.

Parameters
[in]ttNomNominal transmit time ( $\widetilde{t}_t^{sv}$).
[in]prMeasured pseudorange to initialize time-of-flight ( $p$).
[in]rxReceiver position ( $\mathbf{r}^{sv}(t_t)$).
[in]satSatellite ID to get the position for.
[in]navLibThe navigation data library to use for looking up satellite XVT.
[in]orderSpecify whether to search by receiver behavior or by nearest to when in time.
[in]xmitHealthThe desired health status of the satellite transmitting the nav data.
[in]validSpecify whether to search only for valid or invalid messages, or both.
[in]ellipsoidEllipsoid model to provide an ECEF rotation rate.
Returns
The corrected range from rx to sat at ttNom.

Definition at line 165 of file EphemerisRange.cpp.

◆ ComputeAtTransmitTime() [1/2]

double gnsstk::CorrectedEphemerisRange::ComputeAtTransmitTime ( const CommonTime trNom,
const double &  pr,
const Position rx,
const SatID  sat,
NavLibrary navLib,
NavSearchOrder  order = NavSearchOrder::User,
SVHealth  xmitHealth = SVHealth::Any,
NavValidityType  valid = NavValidityType::ValidOnly,
const EllipsoidModel ellipsoid = GPSEllipsoid() 
)

Compute the corrected range at TRANSMIT time (receiver time frame) from rx to sat at trNom.

Note
The name of the method is slightly misleading. This uses a RX's nominal receive time to compute the distance between a RX at nominal receive time and an SV at transmit time.

This uses a simple rearrangement of the RX pseudorange equation to determine a nominal time of signal transmission ( $t_t$).

\begin{eqnarray*} p &=& c(\widetilde{t}_r^{rx} - \widetilde{t}_t^{sv}) \\ \Rightarrow \widetilde{t}_t^{sv} &=& \widetilde{t}_r^{rx} - p/c \end{eqnarray*}

The nominal transmission time is corrected with SV clock offsets to compute the true transmission time.

\begin{eqnarray*} t_t &=& \widetilde{t}_t^{sv} - dt^{sv}(\widetilde{t}_t^{sv}) \\ &=& \widetilde{t}_r^{rx} - p/c - dt^{sv}(\widetilde{t}_t^{sv}) \end{eqnarray*}

Note that any RX clock bias drops out as the bias is present in both the RX's timestamp ( $\widetilde{t}_r^{rx}$) and in the pseudorange. With the transmit time computed, a geometric range is computed using the equation described in class description.

Parameters
[in]trNomNominal recieve time ( $\widetilde{t}_r^{rx}$).
[in]prMeasured pseudorange to initialize time-of-flight ( $p$).
[in]rxReceiver position ( $\mathbf{r}^{sv}(t_t)$).
[in]satSatellite ID to get the position for.
[in]navLibThe navigation data library to use for looking up satellite XVT.
[in]orderSpecify whether to search by receiver behavior or by nearest to when in time.
[in]xmitHealthThe desired health status of the satellite transmitting the nav data.
[in]validSpecify whether to search only for valid or invalid messages, or both.
[in]ellipsoidEllipsoid model to provide an ECEF rotation rate.
Returns
The corrected range from rx to sat at trNom.

Definition at line 102 of file EphemerisRange.cpp.

◆ ComputeAtTransmitTime() [2/2]

double gnsstk::CorrectedEphemerisRange::ComputeAtTransmitTime ( const CommonTime trNom,
const Position rx,
const SatID  sat,
NavLibrary navLib,
NavSearchOrder  order = NavSearchOrder::User,
SVHealth  xmitHealth = SVHealth::Any,
NavValidityType  valid = NavValidityType::ValidOnly,
const EllipsoidModel ellipsoid = GPSEllipsoid() 
)

Compute the corrected range at TRANSMIT time (receiver time frame), from rx to sat at trNom.

Note
The name of the method is slightly misleading. This uses a RX's apparent receive time to compute the distance between a RX at apparent receive time and an SV at transmit time.
Note
This doesn't use a pseudorange to initialize the time-of-flight computation; however note that this could be problematic since the measured pseudorange includes the rx clock bias while this does not; prefer the version with measured pseudorange input.

This uses the same methodology as ComputeAtTransmitTime with the pseudorange input, but instead of a using a direct pseudorange obseravation one is generated using the provided receiver position and the SV's position at the nominal receive time.

Parameters
[in]trNomNominal receive time ( $\widetilde{t}_r^{rx}$).
[in]rxReceiver position ( $\mathbf{r}^{sv}(t_t)$).
[in]satSatellite ID to get the position for.
[in]navLibThe navigation data library to use for looking up satellite XVT.
[in]orderSpecify whether to search by receiver behavior or by nearest to when in time.
[in]xmitHealthThe desired health status of the satellite transmitting the nav data.
[in]validSpecify whether to search only for valid or invalid messages, or both.
[in]ellipsoidEllipsoid model to provide an ECEF rotation rate.
Returns
The corrected range from rx to sat at trNom.

Definition at line 133 of file EphemerisRange.cpp.

◆ updateCER()

void gnsstk::CorrectedEphemerisRange::updateCER ( const Position rx)
private

Definition at line 200 of file EphemerisRange.cpp.

Member Data Documentation

◆ azimuth

double gnsstk::CorrectedEphemerisRange::azimuth

The satellite azimuth (spheroidal), as seen at the receiver, in degrees.

Definition at line 266 of file EphemerisRange.hpp.

◆ azimuthGeodetic

double gnsstk::CorrectedEphemerisRange::azimuthGeodetic

The satellite azimuth (geodetic), as seen at the receiver, in degrees.

Definition at line 272 of file EphemerisRange.hpp.

◆ cosines

Triple gnsstk::CorrectedEphemerisRange::cosines

The direction cosines of the satellite, as seen at the receiver (XYZ).

Definition at line 277 of file EphemerisRange.hpp.

◆ elevation

double gnsstk::CorrectedEphemerisRange::elevation

The satellite elevation (spheroidal), as seen at the receiver, in degrees.

Definition at line 263 of file EphemerisRange.hpp.

◆ elevationGeodetic

double gnsstk::CorrectedEphemerisRange::elevationGeodetic

The satellite elevation (geodetic), as seen at the receiver, in degrees.

Definition at line 269 of file EphemerisRange.hpp.

◆ health

vshort gnsstk::CorrectedEphemerisRange::health

The health bits from the GPS LNAV ephemeris, invalid for other GNSSes

Definition at line 284 of file EphemerisRange.hpp.

◆ iodc

vshort gnsstk::CorrectedEphemerisRange::iodc

The IODC of the GPS LNAV ephemeris, invalid for other GNSSes.

Definition at line 281 of file EphemerisRange.hpp.

◆ rawrange

double gnsstk::CorrectedEphemerisRange::rawrange

The computed raw (geometric) range in meters.

Definition at line 254 of file EphemerisRange.hpp.

◆ relativity

double gnsstk::CorrectedEphemerisRange::relativity

The relativity correction in meters.

Definition at line 260 of file EphemerisRange.hpp.

◆ svclkbias

double gnsstk::CorrectedEphemerisRange::svclkbias

The satellite clock bias in meters.

Definition at line 256 of file EphemerisRange.hpp.

◆ svclkdrift

double gnsstk::CorrectedEphemerisRange::svclkdrift

The satellite clock drift in m/s.

Definition at line 258 of file EphemerisRange.hpp.

◆ svPosVel

Xvt gnsstk::CorrectedEphemerisRange::svPosVel

The satellite position (m) and velocity (m/s) in ECEF coordinates.

Definition at line 279 of file EphemerisRange.hpp.

◆ transmit

CommonTime gnsstk::CorrectedEphemerisRange::transmit

The computed transmit time of the signal.

Definition at line 274 of file EphemerisRange.hpp.


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


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