Static Public Member Functions | List of all members
gnsstk::RawRange Class Reference

Detailed Description

Compute the raw range (a.k.a. geometric range) from a receiver at at receive time and an SV at transmit time.

When working with coordinates in an ECEF frame, the rotation of the frame during the transmission must be accounted for in computing the distance. The range equation can be written as such:

\[ \rho(\tau, t_{sv}) = \biggl|\biggl|\mathbf{R3}\bigl(\tau*\omega\bigl)\cdot r^{sv}(t_{sv}) - r^{rx}\biggl|\biggl| \]

The computeRange() methods perform this exact computation. Note that a simple rotation around the Z axis can be used due to the assumption of a short time of flight (<1s). This will not work for larger time deltas.

The above range equation requires knowing the transmit time and the time of flight (tof) but usually neither is known. There are several RawRange methods for estimating the transmit time and tof depending on the available inputs.

Documentation and code in this class tries to stay consistent in terminology. The table below describes the terminology.

Term Variable Name Math Term Explanation
R3 N/A $\mathbf{R3}$ A rotation about the Z axis
Time of flight (tof) tof $\tau$ The time it takes from signal transmission to signal reception
Angular velocity N/A $\omega$ An ECEF reference frame's angular velocity, typically provided by an ellipsoid model
Receiver (RX) position rxPos $r^{rx}$ A receiver's position in ECEF coordinates
SV position svPos $r^{sv}$ An SV's position in ECEF coordinates
Nominal receive time receiveNominal $\tilde{t}_{rx}$ The receive time in the time frame of the receiver.
Receive time receive $t_{rx}$ The true receive time
Nominal transmit time transmitNominal $\tilde{t}_{sv}$ The transmit time in the time frame of the transmitter (e.g. SV)
Transmit time transmit $t_{sv}$ The true transmit time
SV clock offset N/A $\Delta t_{sv}$ An SV clock's offset from a true time frame (typically GPS)

RX relativity correction | $\delta t_{sv}^{rel}$ | A relativity correction due to the ellipictal orbits of SVs

Definition at line 113 of file RawRange.hpp.

#include <RawRange.hpp>

Static Public Member Functions

static std::tuple< double, PositioncomputeRange (const Position &rxPos, const CommonTime &receive, const Position &svPos, const CommonTime &transmit, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false)
 
static std::tuple< double, XvtcomputeRange (const Position &rxPos, const CommonTime &receive, const Xvt &svXvt, const CommonTime &transmit, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false)
 
static std::tuple< double, PositioncomputeRange (const Position &rxPos, const Position &svPos, double tof, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false)
 
static std::tuple< double, XvtcomputeRange (const Position &rxPos, const Xvt &svXvt, double tof, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false)
 
static std::tuple< bool, CommonTimeestTransmitFromObs (const CommonTime &receiveNominal, double pseudorange, NavLibrary &navLib, const NavSatelliteID &sat, SVHealth xmitHealth=SVHealth::Any, NavValidityType valid=NavValidityType::ValidOnly, NavSearchOrder order=NavSearchOrder::User)
 
static std::tuple< bool, CommonTimeestTransmitFromReceive (const Position &rxPos, const CommonTime &receive, NavLibrary &navLib, const NavSatelliteID &sat, const EllipsoidModel &ellipsoid, SVHealth xmitHealth=SVHealth::Any, NavValidityType valid=NavValidityType::ValidOnly, NavSearchOrder order=NavSearchOrder::User, double seed=0.07, double threshold=1.e-13, int maxIter=5)
 
static std::tuple< bool, double, XvtfromNominalReceive (const Position &rxPos, const CommonTime &receiveNominal, NavLibrary &navLib, const NavSatelliteID &sat, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false, SVHealth xmitHealth=SVHealth::Any, NavValidityType valid=NavValidityType::ValidOnly, NavSearchOrder order=NavSearchOrder::User, double seed=0.7, double threshold=1.e-13, int maxIter=5)
 
static std::tuple< bool, double, XvtfromNominalReceiveWithObs (const Position &rxPos, const CommonTime &receiveNominal, double pseudorange, NavLibrary &navLib, const NavSatelliteID &sat, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false, SVHealth xmitHealth=SVHealth::Any, NavValidityType valid=NavValidityType::ValidOnly, NavSearchOrder order=NavSearchOrder::User)
 
static std::tuple< bool, double, XvtfromReceive (const Position &rxPos, const CommonTime &receive, NavLibrary &navLib, const NavSatelliteID &sat, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false, SVHealth xmitHealth=SVHealth::Any, NavValidityType valid=NavValidityType::ValidOnly, NavSearchOrder order=NavSearchOrder::User, double seed=0.07, double threshold=1.e-13, int maxIter=5)
 
static std::tuple< bool, double, XvtfromSvPos (const Position &rxPos, const Xvt &svXvt, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false, double seed=0.07, double threshold=1.e-13, int maxIter=5)
 
static std::tuple< bool, double, XvtfromSvTransmit (const Position &rxPos, NavLibrary &navLib, const NavSatelliteID &sat, const CommonTime &transmit, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false, SVHealth xmitHealth=SVHealth::Any, NavValidityType valid=NavValidityType::ValidOnly, NavSearchOrder order=NavSearchOrder::User, double seed=0.07, double threshold=1.e-13, int maxIter=5)
 
static std::tuple< bool, double, XvtfromSvTransmitWithObs (const Position &rxPos, double pseudorange, NavLibrary &navLib, const NavSatelliteID &sat, const CommonTime &transmit, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false, SVHealth xmitHealth=SVHealth::Any, NavValidityType valid=NavValidityType::ValidOnly, NavSearchOrder order=NavSearchOrder::User)
 
static Position rotateECEF (const Position &vec, double dt, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false)
 
static Triple rotateECEF (const Triple &vec, double dt, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false)
 
static Xvt rotateECEF (const Xvt &xvt, double dt, const EllipsoidModel &ellipsoid, bool smallAngleApprox=false)
 

Member Function Documentation

◆ computeRange() [1/4]

std::tuple< double, Position > gnsstk::RawRange::computeRange ( const Position rxPos,
const CommonTime receive,
const Position svPos,
const CommonTime transmit,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false 
)
static

Compute geometric range from an SV's transmitting position to a receiver's position and accounting for the rotation of the ECEF frame during the time of flight.

The computation is equiavalent to

\[ \rho = \biggl|\biggl|\mathbf{R3}\bigl((t_{rx} - t_{tx})*\omega)\bigl)\cdot r^{sv} - r^{rx}\biggl|\biggl| \]

Note
An approximation of ECEF rotation is used that is applicable for small time deltas (<1s). Do not use this method for larger rotations.
Parameters
[in]rxPos( $r^rx$) The receiver's position in ECEF coordinates
[in]receive( $t_{rx}$) The time of signal receive
[in]svPos( $r^sv$) The SV's position in ECEF coordinates
[in]transmit( $t_{tx}$) The time of signal transmit
[in]ellipsoidUsed to provide an angular rate of rotation of the ECEF ( $\omega$)
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
Returns
A tuple of the range ( $\rho$) and the rotated SV coordinates ( $\mathbf{R3}(\tau*\omega)\cdot r^{sv}$)

Definition at line 395 of file RawRange.cpp.

◆ computeRange() [2/4]

std::tuple< double, Xvt > gnsstk::RawRange::computeRange ( const Position rxPos,
const CommonTime receive,
const Xvt svXvt,
const CommonTime transmit,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false 
)
static

Compute geometric range from an SV's transmitting position to a receiver's position and accounting for the rotation of the ECEF frame during the time of flight.

The computation is equiavalent to

\[ \rho = \biggl|\biggl|\mathbf{R3}\bigl((t_{rx} - t_{tx})*\omega)\bigl)\cdot r^{sv} - r^{rx}\biggl|\biggl| \]

Note
An approximation of ECEF rotation is used that is applicable for small time deltas (<1s). Do not use this method for larger rotations.
Parameters
[in]rxPos( $r^rx$) The receiver's position in ECEF coordinates
[in]receive( $t_{rx}$) The time of signal receive
[in]svPos( $r^sv$) The SV's position in ECEF coordinates
[in]transmit( $t_{tx}$) The time of signal transmit
[in]ellipsoidUsed to provide an angular rate of rotation of the ECEF ( $\omega$)
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
Returns
A tuple of the range ( $\rho$) and the rotated SV coordinates ( $\mathbf{R3}(\tau*\omega)\cdot r^{sv}$)

Definition at line 371 of file RawRange.cpp.

◆ computeRange() [3/4]

std::tuple< double, Position > gnsstk::RawRange::computeRange ( const Position rxPos,
const Position svPos,
double  tof,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false 
)
static

Compute geometric range from an SV's transmitting position to a receiver's position and accounting for the rotation of the ECEF frame during the time of flight.

The computation is equiavalent to

\[ \rho = \biggl|\biggl|\mathbf{R3}\bigl(\tau*\omega\bigl)\cdot r^{sv} - r^{rx}\biggl|\biggl| \]

Note
An approximation of ECEF rotation is used that is applicable for small time deltas (<1s). Do not use this method for larger rotations.
Parameters
[in]rxPos( $r^rx$) The receiver's position in ECEF coordinates
[in]svPos( $r^sv$) The SV's position in ECEF coordinates
[in]tof( $\tau$) The time of flight between transmission and reception
[in]ellipsoidUsed to provide an angular rate of rotation of the ECEF ( $\omega$)
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
Returns
A tuple of the range ( $\rho$) and the rotated SV coordinates ( $\mathbf{R3}(\tau*\omega)\cdotr^{sv}$)

Definition at line 407 of file RawRange.cpp.

◆ computeRange() [4/4]

std::tuple< double, Xvt > gnsstk::RawRange::computeRange ( const Position rxPos,
const Xvt svXvt,
double  tof,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false 
)
static

Compute geometric range from an SV's transmitting position to a receiver's position and accounting for the rotation of the ECEF frame during the time of flight.

The computation is equiavalent to

\[ \rho = \biggl|\biggl|\mathbf{R3}\bigl(\tau*\omega\bigl)\cdot r^{sv} - r^{rx}\biggl|\biggl| \]

Note
An approximation of ECEF rotation is used that is applicable for small time deltas (<1s). Do not use this method for larger rotations.
Parameters
[in]rxPos( $r^rx$) The receiver's position in ECEF coordinates
[in]svXvtThe SV's position ( $r^sv$) and velocity in ECEF coordinates
[in]tof( $\tau$) The time of flight between transmission and reception
[in]ellipsoidUsed to provide an angular rate of rotation of the ECEF ( $\omega$)
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
Returns
A tuple of the range ( $\rho$) and the rotated SV position and velocity

Definition at line 383 of file RawRange.cpp.

◆ estTransmitFromObs()

std::tuple< bool, CommonTime > gnsstk::RawRange::estTransmitFromObs ( const CommonTime receiveNominal,
double  pseudorange,
NavLibrary navLib,
const NavSatelliteID sat,
SVHealth  xmitHealth = SVHealth::Any,
NavValidityType  valid = NavValidityType::ValidOnly,
NavSearchOrder  order = NavSearchOrder::User 
)
static

Estimate signal transmission time using receiver observations and ephemeris.

A pseudorange is typically formed as the difference between nominal receive time and nominal transmit time, multiplied by the speed of light.

\[ p = c * (\tilde{t}_{rx} - \tilde{t}_{sv}) \]

The nominal transmit time consists of the actual transmit time plus clock offsets at the time of broadcast. Clock offsets are provided by SV ephemeris broadcasts.

\[ p = c * (\tilde{t}_{rx} - t_{sv} - \Delta t_{sv} - \delta t_{sv}^{rel}) \]

Solving for transmit time, we get:

\[ t_{sv} = \tilde{t}_{rx} - \frac{p}{c} - \Delta t_{sv} - \delta t_{sv}^{rel} \]

Note
Other biases like ISCs and second order relativity are not accounted for here. Additional corrections can be applied to the output by subtracting any additional known biases.
Parameters
[in]receiveNominalThe receive time in the time frame of the receiver
[in]pseudorangeMeasured pseudorange at the nominal receive time
[in]navLibThe navigation data library to use for looking up satellite XVT.
[in]satSatellite ID to get the position for.
[in]xmitHealthThe desired health status of the transmitting satellite.
[in]validSpecify whether to search only for valid or invalid messages, or both.
[in]orderSpecify whether to search by receiver behavior or by nearest to when in time.
Returns
A tuple of success code and estimated transmit time. The bool is true if successful, false if no nav data was found to compute the Xvt

Definition at line 347 of file RawRange.cpp.

◆ estTransmitFromReceive()

std::tuple< bool, CommonTime > gnsstk::RawRange::estTransmitFromReceive ( const Position rxPos,
const CommonTime receive,
NavLibrary navLib,
const NavSatelliteID sat,
const EllipsoidModel ellipsoid,
SVHealth  xmitHealth = SVHealth::Any,
NavValidityType  valid = NavValidityType::ValidOnly,
NavSearchOrder  order = NavSearchOrder::User,
double  seed = 0.07,
double  threshold = 1.e-13,
int  maxIter = 5 
)
static

Estimate a transmit time using a known receive time and geometric constraints.

This method estimates a transmit time by finding the optimal solution to the set of equations:

\[ t_{sv} = t_{rx} - \tau \]

\[ \rho(\tau, t_{sv}) = \biggl|\biggl|\mathbf{R3}\bigl(\tau*\omega\bigl)\cdot r^{sv}(t_{sv}) - r^{rx}\biggl|\biggl| \]

\[ \tau = \rho(\tau, t_{sv}) / c \]

The above equations are evaluated iteratively until an end condition is met.

Parameters
[in]rxPosA receiver's position in ECEF
[in]navLibThe navigation data library to use for looking up satellite XVT.
[in]satSatellite ID to get the position for.
[in]ellipsoidEllipsoid model to provide an ECEF rotation rate.
[in]xmitHealthThe desired health status of the transmitting satellite.
[in]validSpecify whether to search only for valid or invalid messages, or both.
[in]orderSpecify whether to search by receiver behavior or by nearest to when in time.
[in]seedAn initial guess of the time of flight ( $\tau$)
[in]thresholdConvergence threshold
[in]maxIterMax number of iterations to evaluate
Returns
A tuple of success code and estimated transmit time. The bool is true if successful, false if no nav data was found to compute the Xvt

Definition at line 298 of file RawRange.cpp.

◆ fromNominalReceive()

std::tuple< bool, double, Xvt > gnsstk::RawRange::fromNominalReceive ( const Position rxPos,
const CommonTime receiveNominal,
NavLibrary navLib,
const NavSatelliteID sat,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false,
SVHealth  xmitHealth = SVHealth::Any,
NavValidityType  valid = NavValidityType::ValidOnly,
NavSearchOrder  order = NavSearchOrder::User,
double  seed = 0.7,
double  threshold = 1.e-13,
int  maxIter = 5 
)
static

Compute geometric range from an SV's transmitting positioning

Uses a combination of fromSvTransmit() and fromNominalReceiveWithObs to estimate the range from SV to RX.

Parameters
[in]rxPosA receiver's position in ECEF
[in]receiveNominalThe receive time in the time frame of the receiver
[in]navLibThe navigation data library to use for looking up satellite XVT.
[in]satSatellite ID to get the position for.
[in]ellipsoidEllipsoid model to provide an ECEF rotation rate.
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
[in]xmitHealthThe desired health status of the transmitting satellite.
[in]validSpecify whether to search only for valid or invalid messages, or both.
[in]orderSpecify whether to search by receiver behavior or by nearest to when in time.
[in]seedAn initial guess of the time of flight ( $\tau$)
[in]thresholdConvergence threshold
[in]maxIterMax number of iterations to evaluate
Returns
A tuple of success code, raw range, and rotated SV coordinates. The bool is true if successful, false if no nav data was found to compute the Xvt.

Definition at line 199 of file RawRange.cpp.

◆ fromNominalReceiveWithObs()

std::tuple< bool, double, Xvt > gnsstk::RawRange::fromNominalReceiveWithObs ( const Position rxPos,
const CommonTime receiveNominal,
double  pseudorange,
NavLibrary navLib,
const NavSatelliteID sat,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false,
SVHealth  xmitHealth = SVHealth::Any,
NavValidityType  valid = NavValidityType::ValidOnly,
NavSearchOrder  order = NavSearchOrder::User 
)
static

Compute geometric range from receiver observations

This is the common approach to computing raw range when provided receiver observations. It uses estTransmitFromObs to generate a transmit time and then compute raw range.

Parameters
[in]rxPosA receiver's position in ECEF
[in]receiveNominalThe receive time in the time frame of the receiver
[in]pseudorangeMeasured pseudorange at the nominal receive time
[in]navLibThe navigation data library to use for looking up satellite XVT.
[in]satSatellite ID to get the position for.
[in]ellipsoidEllipsoid model to provide an ECEF rotation rate.
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
[in]xmitHealthThe desired health status of the transmitting satellite.
[in]validSpecify whether to search only for valid or invalid messages, or both.
[in]orderSpecify whether to search by receiver behavior or by nearest to when in time.
Returns
A tuple of success code, raw range, and rotated SV coordinates. The bool is true if successful, false if no nav data was found to compute the Xvt.

Definition at line 242 of file RawRange.cpp.

◆ fromReceive()

std::tuple< bool, double, Xvt > gnsstk::RawRange::fromReceive ( const Position rxPos,
const CommonTime receive,
NavLibrary navLib,
const NavSatelliteID sat,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false,
SVHealth  xmitHealth = SVHealth::Any,
NavValidityType  valid = NavValidityType::ValidOnly,
NavSearchOrder  order = NavSearchOrder::User,
double  seed = 0.07,
double  threshold = 1.e-13,
int  maxIter = 5 
)
static

Compute geometric range at a known receive time

Parameters
[in]rxPosA receiver's position in ECEF
[in]receiveThe receive time
[in]navLibThe navigation data library to use for looking up satellite XVT.
[in]satSatellite ID to get the position for.
[in]ellipsoidEllipsoid model to provide an ECEF rotation rate.
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
[in]xmitHealthThe desired health status of the transmitting satellite.
[in]validSpecify whether to search only for valid or invalid messages, or both.
[in]orderSpecify whether to search by receiver behavior or by nearest to when in time.
[in]seedAn initial guess of the time of flight ( $\tau$)
[in]thresholdConvergence threshold
[in]maxIterMax number of iterations to evaluate
Returns
A tuple of success code, raw range, and rotated SV coordinates. The bool is true if successful, false if no nav data was found to compute the Xvt.

Definition at line 150 of file RawRange.cpp.

◆ fromSvPos()

std::tuple< bool, double, Xvt > gnsstk::RawRange::fromSvPos ( const Position rxPos,
const Xvt svXvt,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false,
double  seed = 0.07,
double  threshold = 1.e-13,
int  maxIter = 5 
)
static

Compute geometric range from an SV's known transmitting position.

This method estimates a transmit time by holding the SV position as constant and finding the optimal solution to the set of equations:

\[ \rho(\tau) = \biggl|\biggl|\mathbf{R3}\bigl(\tau*\omega\bigl)\cdot r^{sv} - r^{rx}\biggl|\biggl| \]

\[ \tau = \rho(\tau) / c \]

Parameters
[in]rxPosA receiver's position in ECEF
[in]svXvtAn SV's Xvt
[in]ellipsoidEllipsoid model to provide an ECEF rotation rate.
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
[in]seedAn initial guess of the time of flight ( $\tau$)
[in]thresholdConvergence threshold
[in]maxIterMax number of iterations to evaluate
Returns
A tuple of success code, raw range, and rotated SV coordinates. The bool is true if successful, false if no nav data was found to compute the Xvt.

Definition at line 57 of file RawRange.cpp.

◆ fromSvTransmit()

std::tuple< bool, double, Xvt > gnsstk::RawRange::fromSvTransmit ( const Position rxPos,
NavLibrary navLib,
const NavSatelliteID sat,
const CommonTime transmit,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false,
SVHealth  xmitHealth = SVHealth::Any,
NavValidityType  valid = NavValidityType::ValidOnly,
NavSearchOrder  order = NavSearchOrder::User,
double  seed = 0.07,
double  threshold = 1.e-13,
int  maxIter = 5 
)
static

Compute geometric range from an SV's transmitting position

This method is the same as RawRange::fromSvPos() but will look up the SV position for you by the provided time and NavLibrary.

Parameters
[in]rxPosA receiver's position in ECEF
[in]navLibThe navigation data library to use for looking up satellite XVT.
[in]satSatellite ID to get the position for.
[in]transmitThe transmit time
[in]ellipsoidEllipsoid model to provide an ECEF rotation rate.
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
[in]xmitHealthThe desired health status of the transmitting satellite.
[in]validSpecify whether to search only for valid or invalid messages, or both.
[in]orderSpecify whether to search by receiver behavior or by nearest to when in time.
[in]seedAn initial guess of the time of flight ( $\tau$)
[in]thresholdConvergence threshold
[in]maxIterMax number of iterations to evaluate
Returns
A tuple of success code, raw range, and rotated SV coordinates. The bool is true if successful, false if no nav data was found to compute the Xvt.

Definition at line 90 of file RawRange.cpp.

◆ fromSvTransmitWithObs()

std::tuple< bool, double, Xvt > gnsstk::RawRange::fromSvTransmitWithObs ( const Position rxPos,
double  pseudorange,
NavLibrary navLib,
const NavSatelliteID sat,
const CommonTime transmit,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false,
SVHealth  xmitHealth = SVHealth::Any,
NavValidityType  valid = NavValidityType::ValidOnly,
NavSearchOrder  order = NavSearchOrder::User 
)
static

Compute geometric range using a known transmit time and pseudorange measurement.

This is specifically used for smoothed observations which are time stamped by SV transmit time.

Parameters
[in]rxPosA receiver's position in ECEF
[in]pseudorangeA measured pseudorange
[in]navLibThe navigation data library to use for looking up satellite XVT.
[in]satSatellite ID to get the position for.
[in]ellipsoidEllipsoid model to provide an ECEF rotation rate.
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
[in]xmitHealthThe desired health status of the transmitting satellite.
[in]validSpecify whether to search only for valid or invalid messages, or both.
[in]orderSpecify whether to search by receiver behavior or by nearest to when in time.
Returns
A tuple of success code, raw range, and rotated SV coordinates. The bool is true if successful, false if no nav data was found to compute the Xvt.

Definition at line 118 of file RawRange.cpp.

◆ rotateECEF() [1/3]

Position gnsstk::RawRange::rotateECEF ( const Position vec,
double  dt,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false 
)
static

Transform ECEF coordinates into rotated ECEF frame

The transformation is equiavalent to

\[ v\prime=\mathbf{R3}(dt*\omega)\cdot v \]

Note
An approximation of ECEF rotation is used that is applicable for small time deltas (<1s). Do not use this method for larger rotations.
Parameters
[in]vecA position. If it is not in ECEF it will first be converted to ECEF before performing rotation.
[in]dtTime of rotation in seconds
[in]ellipsoidProvides the angular rate of the ECEF
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
Returns
A copy vec but with coordinates in the rotated frame. The output Position will be in the same coordinate system as the input vec.

Definition at line 444 of file RawRange.cpp.

◆ rotateECEF() [2/3]

Triple gnsstk::RawRange::rotateECEF ( const Triple vec,
double  dt,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false 
)
static

Transform ECEF coordinates into rotated ECEF frame

The transformation is equiavalent to

\[ v\prime=\mathbf{R3}(dt*\omega)\cdot v \]

Note
An approximation of ECEF rotation is used that is applicable for small time deltas (<1s). Do not use this method for larger rotations.
Parameters
[in]vecAn ECEF vector
[in]dtTime of rotation in seconds
[in]ellipsoidProvides the angular rate of the ECEF
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
Returns
A copy of vec but with coordinates in the rotated frame

Definition at line 420 of file RawRange.cpp.

◆ rotateECEF() [3/3]

Xvt gnsstk::RawRange::rotateECEF ( const Xvt xvt,
double  dt,
const EllipsoidModel ellipsoid,
bool  smallAngleApprox = false 
)
static

Transform ECEF coordinates into rotated ECEF frame

This method will transform both the xvt position and velocity vectors to keep them consistent.

The transformation is equiavalent to

\[ v\prime=\mathbf{R3}(dt*\omega)\cdot v \]

Note
An approximation of ECEF rotation is used that is applicable for small time deltas (<1s). Do not use this method for larger rotations.
Parameters
[in]xvtAn ECEF position and velocity
[in]dtTime of rotation in seconds
[in]ellipsoidProvides the angular rate of the ECEF
[in]smallAngleApproxIf true, uses the small angle approximation to skip trigonometric computations. This can be used to reduce the number of operations but sacrifice precision.
Returns
A copy of the provided Xvt but with the position and velocity vectors in the rotated ECEF frame

Definition at line 462 of file RawRange.cpp.


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


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