0.5.0
Loading...
Searching...
No Matches
NAV::RealTimeKinematic Class Reference

Numerically integrates Imu data. More...

Data Structures

struct  Difference
 Differences (single or double) More...
struct  OutlierInfo
 Outlier removal info. More...
struct  PivotSatellite
 Pivot satellite information. More...
struct  UpdateStatus
 Update Valid information. More...

Public Types

enum  ReceiverType : uint8_t {
  Rover ,
  Base ,
  ReceiverType_COUNT
}
 Receiver Types. More...
Public Types inherited from NAV::Node
enum class  Mode : uint8_t {
  REAL_TIME ,
  POST_PROCESSING
}
 Different Modes the Node can work in. More...
enum class  State : uint8_t {
  Disabled ,
  Deinitialized ,
  DoInitialize ,
  Initializing ,
  Initialized ,
  DoDeinitialize ,
  Deinitializing ,
  DoShutdown ,
  Shutdown
}
 Possible states of the node. More...

Public Member Functions

void guiConfig () override
 ImGui config window which is shown on double click.
RealTimeKinematicoperator= (const RealTimeKinematic &)=delete
 Copy assignment operator.
RealTimeKinematicoperator= (RealTimeKinematic &&)=delete
 Move assignment operator.
 RealTimeKinematic ()
 Default constructor.
 RealTimeKinematic (const RealTimeKinematic &)=delete
 Copy constructor.
 RealTimeKinematic (RealTimeKinematic &&)=delete
 Move constructor.
void restore (const json &j) override
 Restores the node from a json object.
json save () const override
 Saves the node into a json object.
std::string type () const override
 String representation of the Class Type.
 ~RealTimeKinematic () override
 Destructor.
Public Member Functions inherited from NAV::Node
virtual void afterCreateLink (OutputPin &startPin, InputPin &endPin)
 Called when a new link was established.
virtual void afterDeleteLink (OutputPin &startPin, InputPin &endPin)
 Called when a link was deleted.
bool doDeinitialize (bool wait=false)
 Asks the node worker to deinitialize the node.
bool doDisable (bool wait=false)
 Asks the node worker to disable the node.
bool doEnable ()
 Enable the node.
bool doInitialize (bool wait=false)
 Asks the node worker to initialize the node.
bool doReinitialize (bool wait=false)
 Asks the node worker to reinitialize the node.
virtual void flush ()
 Function called by the flow executer after finishing to flush out remaining data.
template<typename T>
std::optional< InputPin::IncomingLink::ValueWrapper< T > > getInputValue (size_t portIndex) const
 Get Input Value connected on the pin. Only const data types.
Mode getMode () const
 Get the current mode of the node.
const ImVec2 & getSize () const
 Get the size of the node.
State getState () const
 Get the current state of the node.
bool hasInputPinWithSameTime (const InsTime &insTime) const
 Checks wether there is an input pin with the same time.
InputPininputPinFromId (ax::NodeEditor::PinId pinId)
 Returns the pin with the given id.
size_t inputPinIndexFromId (ax::NodeEditor::PinId pinId) const
 Returns the index of the pin.
void invokeCallbacks (size_t portIndex, const std::shared_ptr< const NodeData > &data)
 Calls all registered callbacks on the specified output port.
bool isDisabled () const
 Checks if the node is disabled.
bool isInitialized () const
 Checks if the node is initialized.
bool isOnlyRealtime () const
 Checks if the node is only working in real time (sensors, network interfaces, ...)
bool isTransient () const
 Checks if the node is changing its state currently.
std::string nameId () const
 Node name and id.
 Node (const Node &)=delete
 Copy constructor.
 Node (Node &&)=delete
 Move constructor.
 Node (std::string name)
 Constructor.
void notifyOutputValueChanged (size_t pinIdx, const InsTime &insTime, const std::scoped_lock< std::mutex > &&guard)
 Notifies connected nodes about the change.
virtual bool onCreateLink (OutputPin &startPin, InputPin &endPin)
 Called when a new link is to be established.
virtual void onDeleteLink (OutputPin &startPin, InputPin &endPin)
 Called when a link is to be deleted.
Nodeoperator= (const Node &)=delete
 Copy assignment operator.
Nodeoperator= (Node &&)=delete
 Move assignment operator.
OutputPinoutputPinFromId (ax::NodeEditor::PinId pinId)
 Returns the pin with the given id.
size_t outputPinIndexFromId (ax::NodeEditor::PinId pinId) const
 Returns the index of the pin.
void releaseInputValue (size_t portIndex)
 Unblocks the connected node. Has to be called when the input value should be released and getInputValue was not called.
std::scoped_lock< std::mutex > requestOutputValueLock (size_t pinIdx)
 Blocks the thread till the output values was read by all connected nodes.
virtual bool resetNode ()
 Resets the node. It is guaranteed that the node is initialized when this is called.
virtual void restoreAtferLink (const json &j)
 Restores link related properties of the node from a json object.
void wakeWorker ()
 Wakes the worker thread.
virtual ~Node ()
 Destructor.

Static Public Member Functions

static std::string category ()
 String representation of the Class Category.
static std::string typeStatic ()
 String representation of the Class Type.
Static Public Member Functions inherited from NAV::Node
static std::string toString (State state)
 Converts the state into a printable text.

Private Types

using Differences
 Difference storage type.
using Receiver
 Receiver.
enum class  StdevAccelUnits : uint8_t { m_sqrts3 }
 Possible Units for the Standard deviation of the acceleration due to user motion. More...
enum class  StdevAmbiguityUnits : uint8_t { Cycle }
 Possible Units for the Standard deviation of the ambiguities. More...

Private Member Functions

void addEventToGui (const std::shared_ptr< RtkSolution > &rtkSol, const std::string &text)
 Adds the event to the GUI list.
void addOrRemoveKalmanFilterAmbiguities (const Observations &observations, const std::shared_ptr< RtkSolution > &rtkSol)
 Adds or remove Ambiguities to/from the Kalman Filter state depending on the received observations.
void applyFixedAmbiguities (const Eigen::VectorXd &fixedAmb, const std::vector< RTK::States::StateKeyType > &ambKeys, const std::vector< RTK::Meas::MeasKeyTypes > &ambMeasKeys)
 Apply the fixed ambiguities to the kalman filter state.
void assignSolutionToFilter (const std::shared_ptr< NAV::SppSolution > &sppSol)
 Assign the SPP solution to the RTK filter.
Differences calcDoubleDifferences (const Observations &observations, const Differences &singleDifferences) const
 Calculates the double difference of the measurements and estimates.
std::shared_ptr< RtkSolutioncalcFallbackSppSolution ()
 Calculates a SPP solution as fallback in case no base data is available.
void calcKalmanUpdateMatrices (const Observations &observations, const Differences &doubleDifferences, const unordered_map< GnssObs::ObservationType, KeyedMatrixXd< RTK::Meas::SingleObs< ReceiverType > > > &Rtilde)
 Calculates the Measurement vector 𝐳, Measurement sensitivity matrix 𝐇 and Measurement noise covariance matrix 𝐑 for the KF update.
void calcRealTimeKinematicSolution ()
 Calculates the RTK solution.
Differences calcSingleDifferences (const Observations &observations) const
 Calculates the single difference of the measurements and estimates.
unordered_map< GnssObs::ObservationType, KeyedMatrixXd< RTK::Meas::SingleObs< ReceiverType > > > calcSingleObsMeasurementNoiseMatrices (const Observations &observations) const
 Calculate the measurement noise matrices for each observation type.
void checkForCycleSlip (Observations &observations, const std::shared_ptr< RtkSolution > &rtkSol)
 Checks for cycle-slips.
void deinitialize () override
 Deinitialize the node.
bool initialize () override
 Initialize the node.
void kalmanFilterPrediction ()
 Does the Kalman Filter prediction.
UpdateStatus kalmanFilterUpdate (const std::shared_ptr< RtkSolution > &rtkSol)
 Does the Kalman Filter update.
void printObservations (const Observations &observations)
 Prints the observations for logging.
void printPivotSatellites ()
 Prints all pivot satellites.
void recvBaseGnssObs (InputPin::NodeDataQueue &queue, size_t pinIdx)
 Receive Function for the Base GNSS Observations.
void recvBasePos (InputPin::NodeDataQueue &queue, size_t pinIdx)
 Receive Function for the Base Position.
void recvRoverGnssObs (InputPin::NodeDataQueue &queue, size_t pinIdx)
 Receive Function for the RoverGNSS Observations.
std::vector< OutlierInforemoveOutlier (Observations &observations, const std::shared_ptr< RtkSolution > &rtkSol)
 Performs the NIS check.
void removeSingleObservations (Observations &observations, ObservationFilter::Filtered *filtered, const std::shared_ptr< RtkSolution > &rtkSol)
 Removes observations which do not have a second one to do double differences.
bool resolveAmbiguities (size_t nCarrierMeasUniqueSatellite, const std::shared_ptr< RtkSolution > &rtkSol)
 Resolves the ambiguities in the Kalman filter and updates the state and covariance matrix.
void updateKalmanFilterAmbiguitiesForPivotChange (const SatSigId &newPivotSatSigId, const SatSigId &oldPivotSatSigId, bool oldPivotObservedInEpoch, const std::shared_ptr< RtkSolution > &rtkSol)
 Adapts the Kalman Filter if a pivot satellite signal was changed.
std::optional< RtkSolution::PivotChangeupdatePivotSatellite (Code code, GnssObs::ObservationType obsType, Observations &observations, const std::shared_ptr< RtkSolution > &rtkSol, const RtkSolution::PivotChange::Reason &reason)
 Update the specified pivot satellite and also does a pivot change in the Kalman filter state if necessary.
void updatePivotSatellites (Observations &observations, const std::shared_ptr< RtkSolution > &rtkSol)
 Update the pivot satellites for each constellation.

Static Private Member Functions

static void pinAddCallback (Node *node)
 Function to call to add a new pin.
static void pinDeleteCallback (Node *node, size_t pinIdx)
 Function to call to delete a pin.

Private Attributes

double _ambFixUpdateVariance
 Measurement noise variance used when fixing ambiguities in [cycles^2] (Value used for calculation)
std::unordered_map< SatSigId, double > _ambiguitiesHold
 Ambiguities which are fixed and hold. Values in [cycles].
double _ambiguityFixProcessNoiseVariance
 Process noise (standard deviation) for the ambiguities (while fix solution) in [cycles^2] (Value used for calculation)
double _ambiguityFloatProcessNoiseVariance
 Process noise (variance) for the ambiguities (while float solution) in [cycles^2] (Value used for calculation)
AmbiguityResolutionParameters _ambiguityResolutionParameters
 Ambiguity resolution algorithms and parameters to use.
AmbiguityResolutionStrategy _ambiguityResolutionStrategy
 Ambiguity resolution strategy.
bool _applyFixedAmbiguitiesWithUpdate
bool _baseObsReceivedThisEpoch
 Flag, whether the observation was received this epoch.
bool _calcSPPIfNoBase
 Wether to output a SPP solution if no base observations are available.
std::array< CycleSlipDetector, ReceiverType_COUNT_cycleSlipDetector
 Cycle-slip detector.
double _dataInterval
 Data interval [s].
gui::widgets::DynamicInputPins _dynamicInputPins
 Dynamic input pins.
std::string _eventFilterRegex
 Regex for filtering events.
std::vector< std::pair< InsTime, std::vector< std::string > > > _events
 List of event texts (pivot changes, cycle-slips)
double _gui_ambFixUpdateStdDev
 Measurement noise standard deviation used when fixing ambiguities in [cycles] (GUI value)
StdevAmbiguityUnits _gui_ambFixUpdateStdDevUnits
 Gui selection for the Unit of the input for the StDev of the ambiguities (while float solution)
double _gui_ambiguityFixProcessNoiseStDev
 Process noise (standard deviation) for the ambiguities (while fix solution) (Selection in GUI)
double _gui_ambiguityFloatProcessNoiseStDev
 Process noise (standard deviation) for the ambiguities (while float solution) (Selection in GUI)
std::array< double, 2 > _gui_stdevAccel
 GUI selection for the Standard deviation of the acceleration 𝜎_a due to user motion in horizontal and vertical component.
StdevAccelUnits _gui_stdevAccelUnits
 Gui selection for the Unit of the input stdev_accel parameter for the StDev due to acceleration due to user motion.
StdevAmbiguityUnits _gui_stdevAmbiguityFixUnits
 Gui selection for the Unit of the input for the StDev of the ambiguities (while fix solution)
StdevAmbiguityUnits _gui_stdevAmbiguityFloatUnits
 Gui selection for the Unit of the input for the StDev of the ambiguities (while float solution)
KeyedKalmanFilterD< RTK::States::StateKeyType, RTK::Meas::MeasKeyTypes_kalmanFilter
 Kalman Filter representation.
RtkSolution::SolutionType _lastSolutionStatus
 Solution type of last epoch.
InsTime _lastUpdate
 Last update time.
double _maxPosVar
 Do not attempt to fix if the position variance is above the threshold.
bool _maxPosVarTriggered
 Trigger state of the check.
size_t _maxRemoveOutlier
 Maximum amount of outliers to remove per epoch.
double _maxTimeBetweenBaseRoverForRTK
 Maximum time between base and rover observations to calculate the RTK solution.
size_t _nCycleSlipsDual
 Cycle-slip detection count (Dual)
size_t _nCycleSlipsLLI
 Cycle-slip detection count (LLI)
size_t _nCycleSlipsSingle
 Cycle-slip detection count (Single)
size_t _nMeasExcludedNIS
 Measurement excluded due to NIS test count.
size_t _nMinSatForAmbFix
 Minimum amount of satellites with carrier observations to try fixing the solution.
bool _nMinSatForAmbFixTriggered
 Trigger state of the check.
size_t _nMinSatForAmbHold
 Minimum amount of satellites with carrier observations for holding the ambiguities.
bool _nMinSatForAmbHoldTriggered
 Trigger state of the check.
size_t _nPivotChange
 Amount of pivot changes performed.
ObservationEstimator _obsEstimator
 Observation Estimator.
ObservationFilter _obsFilter
 Observation Filter.
double _outlierMaxPosVarStartup
 Do not attempt to remove outlier if the position variance is above the threshold in the startup phase [m^2].
bool _outlierMaxPosVarStartupTriggered
 Trigger state of the check.
size_t _outlierMinPsrObsKeep
 Minumum amount of pseudorange observables to leave when doing a NIS check.
size_t _outlierMinSat
 Minumum amount of satellites for doing a NIS check.
size_t _outlierRemoveEpochs
 Amount of epochs to remove an outlier after being found (1 = only current)
bool _outputStateEvents
 Whether to output state change events.
unordered_map< std::pair< Code, GnssObs::ObservationType >, PivotSatellite_pivotSatellites
 Pivot satellites for each constellation.
std::array< Receiver, ReceiverType::ReceiverType_COUNT_receiver
 Receivers.
SPP::Algorithm _sppAlgorithm
 SPP algorithm.
size_t nFixSolutions
 Percentage of fix solutions.
size_t nFloatSolutions
 Percentage of float solutions.
size_t nSingleSolutions
 Percentage of float solutions.

Static Private Attributes

static constexpr size_t INPUT_PORT_INDEX_BASE_GNSS_OBS
 GnssObs.
static constexpr size_t INPUT_PORT_INDEX_BASE_POS
 Pos.
static constexpr size_t INPUT_PORT_INDEX_GNSS_NAV_INFO
 GnssNavInfo.
static constexpr size_t INPUT_PORT_INDEX_ROVER_GNSS_OBS
 GnssObs.
static constexpr size_t OUTPUT_PORT_INDEX_RTKSOL
 Flow (RtkSol)

Additional Inherited Members

Data Fields inherited from NAV::Node
bool callbacksEnabled
 Enables the callbacks.
ax::NodeEditor::NodeId id
 Unique Id of the Node.
std::vector< InputPininputPins
 List of input pins.
Kind kind
 Kind of the Node.
std::string name
 Name of the Node.
std::vector< OutputPinoutputPins
 List of output pins.
std::multimap< InsTime, std::pair< OutputPin *, size_t > > pollEvents
 Map with callback events (sorted by time)
Protected Attributes inherited from NAV::Node
ImVec2 _guiConfigDefaultWindowSize
bool _hasConfig
 Flag if the config window should be shown.
bool _lockConfigDuringRun
 Lock the config when executing post-processing.
bool _onlyRealTime
 Whether the node can run in post-processing or only real-time.

Detailed Description

Numerically integrates Imu data.

Definition at line 52 of file RealTimeKinematic.hpp.

Member Typedef Documentation

◆ Differences

Difference storage type.

Definition at line 229 of file RealTimeKinematic.hpp.

◆ Receiver

Receiver.

Definition at line 207 of file RealTimeKinematic.hpp.

Member Enumeration Documentation

◆ ReceiverType

Receiver Types.

Enumerator
Rover 

Rover.

Base 

Base.

ReceiverType_COUNT 

Amount of receiver types.

Definition at line 56 of file RealTimeKinematic.hpp.

◆ StdevAccelUnits

enum class NAV::RealTimeKinematic::StdevAccelUnits : uint8_t
strongprivate

Possible Units for the Standard deviation of the acceleration due to user motion.

Enumerator
m_sqrts3 

[ m / √(s^3) ]

Definition at line 180 of file RealTimeKinematic.hpp.

◆ StdevAmbiguityUnits

enum class NAV::RealTimeKinematic::StdevAmbiguityUnits : uint8_t
strongprivate

Possible Units for the Standard deviation of the ambiguities.

Enumerator
Cycle 

[cycle]

Definition at line 107 of file RealTimeKinematic.hpp.

Constructor & Destructor Documentation

◆ RealTimeKinematic() [1/3]

NAV::RealTimeKinematic::RealTimeKinematic ( )

Default constructor.

Definition at line 76 of file RealTimeKinematic.cpp.

◆ ~RealTimeKinematic()

NAV::RealTimeKinematic::~RealTimeKinematic ( )
override

Destructor.

Definition at line 92 of file RealTimeKinematic.cpp.

◆ RealTimeKinematic() [2/3]

NAV::RealTimeKinematic::RealTimeKinematic ( const RealTimeKinematic & )
delete

Copy constructor.

◆ RealTimeKinematic() [3/3]

NAV::RealTimeKinematic::RealTimeKinematic ( RealTimeKinematic && )
delete

Move constructor.

Member Function Documentation

◆ addEventToGui()

void NAV::RealTimeKinematic::addEventToGui ( const std::shared_ptr< RtkSolution > & rtkSol,
const std::string & text )
private

Adds the event to the GUI list.

Parameters
[in,out]rtkSolRtkSolution to update
[in]textText to display

Definition at line 670 of file RealTimeKinematic.cpp.

◆ addOrRemoveKalmanFilterAmbiguities()

void NAV::RealTimeKinematic::addOrRemoveKalmanFilterAmbiguities ( const Observations & observations,
const std::shared_ptr< RtkSolution > & rtkSol )
private

Adds or remove Ambiguities to/from the Kalman Filter state depending on the received observations.

Parameters
[in]observationsList of GNSS observation data used for the calculation of this epoch
[in,out]rtkSolRtkSolution to update

Definition at line 1876 of file RealTimeKinematic.cpp.

◆ applyFixedAmbiguities()

void NAV::RealTimeKinematic::applyFixedAmbiguities ( const Eigen::VectorXd & fixedAmb,
const std::vector< RTK::States::StateKeyType > & ambKeys,
const std::vector< RTK::Meas::MeasKeyTypes > & ambMeasKeys )
private

Apply the fixed ambiguities to the kalman filter state.

Parameters
[in]fixedAmbFixed ambiguities
[in]ambKeysAmbiguity state keys
[in]ambMeasKeysAmbiguity measurement keys

Definition at line 2737 of file RealTimeKinematic.cpp.

◆ assignSolutionToFilter()

void NAV::RealTimeKinematic::assignSolutionToFilter ( const std::shared_ptr< NAV::SppSolution > & sppSol)
private

Assign the SPP solution to the RTK filter.

Parameters
sppSolSPP solution

Definition at line 795 of file RealTimeKinematic.cpp.

◆ calcDoubleDifferences()

RealTimeKinematic::Differences NAV::RealTimeKinematic::calcDoubleDifferences ( const Observations & observations,
const Differences & singleDifferences ) const
nodiscardprivate

Calculates the double difference of the measurements and estimates.

Parameters
[in]observationsList of GNSS observation data used for the calculation of this epoch
[in]singleDifferencesList of single differences

Definition at line 2057 of file RealTimeKinematic.cpp.

◆ calcFallbackSppSolution()

std::shared_ptr< RtkSolution > NAV::RealTimeKinematic::calcFallbackSppSolution ( )
private

Calculates a SPP solution as fallback in case no base data is available.

Definition at line 1147 of file RealTimeKinematic.cpp.

◆ calcKalmanUpdateMatrices()

void NAV::RealTimeKinematic::calcKalmanUpdateMatrices ( const Observations & observations,
const Differences & doubleDifferences,
const unordered_map< GnssObs::ObservationType, KeyedMatrixXd< RTK::Meas::SingleObs< ReceiverType > > > & Rtilde )
private

Calculates the Measurement vector 𝐳, Measurement sensitivity matrix 𝐇 and Measurement noise covariance matrix 𝐑 for the KF update.

Parameters
[in]observationsList of GNSS observation data used for the calculation of this epoch
[in]doubleDifferencesList of double differences
[in]RtildeSingle observation Measurement Noise Covariance Matrix R for each observation type

Definition at line 2155 of file RealTimeKinematic.cpp.

◆ calcRealTimeKinematicSolution()

void NAV::RealTimeKinematic::calcRealTimeKinematicSolution ( )
private

Calculates the RTK solution.

Definition at line 822 of file RealTimeKinematic.cpp.

◆ calcSingleDifferences()

RealTimeKinematic::Differences NAV::RealTimeKinematic::calcSingleDifferences ( const Observations & observations) const
nodiscardprivate

Calculates the single difference of the measurements and estimates.

Parameters
[in]observationsList of GNSS observation data used for the calculation of this epoch

Definition at line 2028 of file RealTimeKinematic.cpp.

◆ calcSingleObsMeasurementNoiseMatrices()

unordered_map< GnssObs::ObservationType, KeyedMatrixXd< RTK::Meas::SingleObs< RealTimeKinematic::ReceiverType > > > NAV::RealTimeKinematic::calcSingleObsMeasurementNoiseMatrices ( const Observations & observations) const
nodiscardprivate

Calculate the measurement noise matrices for each observation type.

Parameters
observationsList of GNSS observation data used for the calculation of this epoch

Definition at line 2112 of file RealTimeKinematic.cpp.

◆ category()

std::string NAV::RealTimeKinematic::category ( )
staticnodiscard

String representation of the Class Category.

Definition at line 107 of file RealTimeKinematic.cpp.

◆ checkForCycleSlip()

void NAV::RealTimeKinematic::checkForCycleSlip ( Observations & observations,
const std::shared_ptr< RtkSolution > & rtkSol )
private

Checks for cycle-slips.

Parameters
[in]observationsList of GNSS observation data used for the calculation of this epoch
[in,out]rtkSolRtkSolution to update

Definition at line 1254 of file RealTimeKinematic.cpp.

◆ deinitialize()

void NAV::RealTimeKinematic::deinitialize ( )
overrideprivatevirtual

Deinitialize the node.

Reimplemented from NAV::Node.

Definition at line 655 of file RealTimeKinematic.cpp.

◆ guiConfig()

void NAV::RealTimeKinematic::guiConfig ( )
overridevirtual

ImGui config window which is shown on double click.

Attention
Don't forget to set _hasConfig to true in the constructor of the node

Reimplemented from NAV::Node.

Definition at line 112 of file RealTimeKinematic.cpp.

◆ initialize()

bool NAV::RealTimeKinematic::initialize ( )
overrideprivatevirtual

Initialize the node.

Reimplemented from NAV::Node.

Definition at line 589 of file RealTimeKinematic.cpp.

◆ kalmanFilterPrediction()

void NAV::RealTimeKinematic::kalmanFilterPrediction ( )
private

Does the Kalman Filter prediction.

Definition at line 1203 of file RealTimeKinematic.cpp.

◆ kalmanFilterUpdate()

RealTimeKinematic::UpdateStatus NAV::RealTimeKinematic::kalmanFilterUpdate ( const std::shared_ptr< RtkSolution > & rtkSol)
private

Does the Kalman Filter update.

Parameters
[in,out]rtkSolRtkSolution to update
Returns
Update valid information

Definition at line 2487 of file RealTimeKinematic.cpp.

◆ operator=() [1/2]

RealTimeKinematic & NAV::RealTimeKinematic::operator= ( const RealTimeKinematic & )
delete

Copy assignment operator.

◆ operator=() [2/2]

RealTimeKinematic & NAV::RealTimeKinematic::operator= ( RealTimeKinematic && )
delete

Move assignment operator.

◆ pinAddCallback()

void NAV::RealTimeKinematic::pinAddCallback ( Node * node)
staticprivate

Function to call to add a new pin.

Parameters
[in,out]nodePointer to this node

Definition at line 660 of file RealTimeKinematic.cpp.

◆ pinDeleteCallback()

void NAV::RealTimeKinematic::pinDeleteCallback ( Node * node,
size_t pinIdx )
staticprivate

Function to call to delete a pin.

Parameters
[in,out]nodePointer to this node
[in]pinIdxInput pin index to delete

Definition at line 665 of file RealTimeKinematic.cpp.

◆ printObservations()

void NAV::RealTimeKinematic::printObservations ( const Observations & observations)
private

Prints the observations for logging.

Parameters
[in]observationsList of GNSS observation data used for the calculation of this epoch

Definition at line 684 of file RealTimeKinematic.cpp.

◆ printPivotSatellites()

void NAV::RealTimeKinematic::printPivotSatellites ( )
private

Prints all pivot satellites.

Definition at line 1682 of file RealTimeKinematic.cpp.

◆ recvBaseGnssObs()

void NAV::RealTimeKinematic::recvBaseGnssObs ( InputPin::NodeDataQueue & queue,
size_t pinIdx )
private

Receive Function for the Base GNSS Observations.

Parameters
[in]queueQueue with all the received data messages
[in]pinIdxIndex of the pin the data is received on

Definition at line 743 of file RealTimeKinematic.cpp.

◆ recvBasePos()

void NAV::RealTimeKinematic::recvBasePos ( InputPin::NodeDataQueue & queue,
size_t pinIdx )
private

Receive Function for the Base Position.

Parameters
[in]queueQueue with all the received data messages
[in]pinIdxIndex of the pin the data is received on

Definition at line 721 of file RealTimeKinematic.cpp.

◆ recvRoverGnssObs()

void NAV::RealTimeKinematic::recvRoverGnssObs ( InputPin::NodeDataQueue & queue,
size_t pinIdx )
private

Receive Function for the RoverGNSS Observations.

Parameters
[in]queueQueue with all the received data messages
[in]pinIdxIndex of the pin the data is received on

Definition at line 768 of file RealTimeKinematic.cpp.

◆ removeOutlier()

std::vector< RealTimeKinematic::OutlierInfo > NAV::RealTimeKinematic::removeOutlier ( Observations & observations,
const std::shared_ptr< RtkSolution > & rtkSol )
private

Performs the NIS check.

Parameters
[in,out]observationsList of GNSS observation data. Elements can be removed
[in,out]rtkSolRtkSolution to update
Returns
Info of the removed outliers

Definition at line 2289 of file RealTimeKinematic.cpp.

◆ removeSingleObservations()

void NAV::RealTimeKinematic::removeSingleObservations ( Observations & observations,
ObservationFilter::Filtered * filtered,
const std::shared_ptr< RtkSolution > & rtkSol )
private

Removes observations which do not have a second one to do double differences.

Parameters
[in]observationsList of GNSS observation data used for the calculation of this epoch
[in]filteredFiltered observations
[in,out]rtkSolRtkSolution to update

Definition at line 1424 of file RealTimeKinematic.cpp.

◆ resolveAmbiguities()

bool NAV::RealTimeKinematic::resolveAmbiguities ( size_t nCarrierMeasUniqueSatellite,
const std::shared_ptr< RtkSolution > & rtkSol )
private

Resolves the ambiguities in the Kalman filter and updates the state and covariance matrix.

Parameters
[in]nCarrierMeasUniqueSatelliteAmount of used
[in,out]rtkSolRtkSolution to update
Returns
True if the ambiguities could be fixed

Definition at line 2536 of file RealTimeKinematic.cpp.

◆ restore()

void NAV::RealTimeKinematic::restore ( const json & j)
overridevirtual

Restores the node from a json object.

Parameters
[in]jJson object with the node state

Reimplemented from NAV::Node.

Definition at line 522 of file RealTimeKinematic.cpp.

◆ save()

json NAV::RealTimeKinematic::save ( ) const
nodiscardoverridevirtual

Saves the node into a json object.

Reimplemented from NAV::Node.

Definition at line 480 of file RealTimeKinematic.cpp.

◆ type()

std::string NAV::RealTimeKinematic::type ( ) const
nodiscardoverridevirtual

String representation of the Class Type.

Implements NAV::Node.

Definition at line 102 of file RealTimeKinematic.cpp.

◆ typeStatic()

std::string NAV::RealTimeKinematic::typeStatic ( )
staticnodiscard

String representation of the Class Type.

Definition at line 97 of file RealTimeKinematic.cpp.

◆ updateKalmanFilterAmbiguitiesForPivotChange()

void NAV::RealTimeKinematic::updateKalmanFilterAmbiguitiesForPivotChange ( const SatSigId & newPivotSatSigId,
const SatSigId & oldPivotSatSigId,
bool oldPivotObservedInEpoch,
const std::shared_ptr< RtkSolution > & rtkSol )
private

Adapts the Kalman Filter if a pivot satellite signal was changed.

Parameters
[in]newPivotSatSigIdNewly added pivot satellite signal
[in]oldPivotSatSigIdOld pivot satellite signal
[in]oldPivotObservedInEpochIndicates if the old pivot satellite is still observed, or is
[in,out]rtkSolRtkSolution to update

Definition at line 1745 of file RealTimeKinematic.cpp.

◆ updatePivotSatellite()

std::optional< RtkSolution::PivotChange > NAV::RealTimeKinematic::updatePivotSatellite ( Code code,
GnssObs::ObservationType obsType,
Observations & observations,
const std::shared_ptr< RtkSolution > & rtkSol,
const RtkSolution::PivotChange::Reason & reason )
private

Update the specified pivot satellite and also does a pivot change in the Kalman filter state if necessary.

Parameters
codeCode for the pivot
obsTypeObservation type of the pivot
observationsList of GNSS observation data used for the calculation of this epoch
rtkSolRtkSolution to update
reasonReason for changing the pivot
Returns
The final pivot change result after the update. Empty if no pivot was selected

Definition at line 1486 of file RealTimeKinematic.cpp.

◆ updatePivotSatellites()

void NAV::RealTimeKinematic::updatePivotSatellites ( Observations & observations,
const std::shared_ptr< RtkSolution > & rtkSol )
private

Update the pivot satellites for each constellation.

Parameters
[in]observationsList of GNSS observation data used for the calculation of this epoch
[in,out]rtkSolRtkSolution to update

Definition at line 1697 of file RealTimeKinematic.cpp.

Field Documentation

◆ _ambFixUpdateVariance

double NAV::RealTimeKinematic::_ambFixUpdateVariance
private

Measurement noise variance used when fixing ambiguities in [cycles^2] (Value used for calculation)

Definition at line 170 of file RealTimeKinematic.hpp.

◆ _ambiguitiesHold

std::unordered_map<SatSigId, double> NAV::RealTimeKinematic::_ambiguitiesHold
private

Ambiguities which are fixed and hold. Values in [cycles].

Definition at line 267 of file RealTimeKinematic.hpp.

◆ _ambiguityFixProcessNoiseVariance

double NAV::RealTimeKinematic::_ambiguityFixProcessNoiseVariance
private

Process noise (standard deviation) for the ambiguities (while fix solution) in [cycles^2] (Value used for calculation)

Definition at line 203 of file RealTimeKinematic.hpp.

◆ _ambiguityFloatProcessNoiseVariance

double NAV::RealTimeKinematic::_ambiguityFloatProcessNoiseVariance
private

Process noise (variance) for the ambiguities (while float solution) in [cycles^2] (Value used for calculation)

Definition at line 196 of file RealTimeKinematic.hpp.

◆ _ambiguityResolutionParameters

AmbiguityResolutionParameters NAV::RealTimeKinematic::_ambiguityResolutionParameters
private

Ambiguity resolution algorithms and parameters to use.

Definition at line 149 of file RealTimeKinematic.hpp.

◆ _ambiguityResolutionStrategy

AmbiguityResolutionStrategy NAV::RealTimeKinematic::_ambiguityResolutionStrategy
private

Ambiguity resolution strategy.

Definition at line 152 of file RealTimeKinematic.hpp.

◆ _applyFixedAmbiguitiesWithUpdate

bool NAV::RealTimeKinematic::_applyFixedAmbiguitiesWithUpdate
private

Make an update with the fixed ambiguities when true. Otherwise apply via $$a = a_fix$$ and $$b = b_float - Q_ba * Q_aa^-1 (a_fix - a_float)$$

Definition at line 163 of file RealTimeKinematic.hpp.

◆ _baseObsReceivedThisEpoch

bool NAV::RealTimeKinematic::_baseObsReceivedThisEpoch
private

Flag, whether the observation was received this epoch.

Definition at line 216 of file RealTimeKinematic.hpp.

◆ _calcSPPIfNoBase

bool NAV::RealTimeKinematic::_calcSPPIfNoBase
private

Wether to output a SPP solution if no base observations are available.

Definition at line 144 of file RealTimeKinematic.hpp.

◆ _cycleSlipDetector

std::array<CycleSlipDetector, ReceiverType_COUNT> NAV::RealTimeKinematic::_cycleSlipDetector
private

Cycle-slip detector.

Definition at line 255 of file RealTimeKinematic.hpp.

◆ _dataInterval

double NAV::RealTimeKinematic::_dataInterval
private

Data interval [s].

Definition at line 249 of file RealTimeKinematic.hpp.

◆ _dynamicInputPins

gui::widgets::DynamicInputPins NAV::RealTimeKinematic::_dynamicInputPins
private

Dynamic input pins.

Attention
This should always be the last variable in the header, because it accesses others through the function callbacks

Definition at line 284 of file RealTimeKinematic.hpp.

◆ _eventFilterRegex

std::string NAV::RealTimeKinematic::_eventFilterRegex
private

Regex for filtering events.

Definition at line 261 of file RealTimeKinematic.hpp.

◆ _events

std::vector<std::pair<InsTime, std::vector<std::string> > > NAV::RealTimeKinematic::_events
private

List of event texts (pivot changes, cycle-slips)

Definition at line 258 of file RealTimeKinematic.hpp.

◆ _gui_ambFixUpdateStdDev

double NAV::RealTimeKinematic::_gui_ambFixUpdateStdDev
private

Measurement noise standard deviation used when fixing ambiguities in [cycles] (GUI value)

Definition at line 166 of file RealTimeKinematic.hpp.

◆ _gui_ambFixUpdateStdDevUnits

StdevAmbiguityUnits NAV::RealTimeKinematic::_gui_ambFixUpdateStdDevUnits
private

Gui selection for the Unit of the input for the StDev of the ambiguities (while float solution)

Definition at line 168 of file RealTimeKinematic.hpp.

◆ _gui_ambiguityFixProcessNoiseStDev

double NAV::RealTimeKinematic::_gui_ambiguityFixProcessNoiseStDev
private

Process noise (standard deviation) for the ambiguities (while fix solution) (Selection in GUI)

Definition at line 201 of file RealTimeKinematic.hpp.

◆ _gui_ambiguityFloatProcessNoiseStDev

double NAV::RealTimeKinematic::_gui_ambiguityFloatProcessNoiseStDev
private

Process noise (standard deviation) for the ambiguities (while float solution) (Selection in GUI)

Definition at line 194 of file RealTimeKinematic.hpp.

◆ _gui_stdevAccel

std::array<double, 2> NAV::RealTimeKinematic::_gui_stdevAccel
private

GUI selection for the Standard deviation of the acceleration 𝜎_a due to user motion in horizontal and vertical component.

Note
See Groves (2013) eq. (9.156)

Definition at line 189 of file RealTimeKinematic.hpp.

◆ _gui_stdevAccelUnits

StdevAccelUnits NAV::RealTimeKinematic::_gui_stdevAccelUnits
private

Gui selection for the Unit of the input stdev_accel parameter for the StDev due to acceleration due to user motion.

Definition at line 185 of file RealTimeKinematic.hpp.

◆ _gui_stdevAmbiguityFixUnits

StdevAmbiguityUnits NAV::RealTimeKinematic::_gui_stdevAmbiguityFixUnits
private

Gui selection for the Unit of the input for the StDev of the ambiguities (while fix solution)

Definition at line 199 of file RealTimeKinematic.hpp.

◆ _gui_stdevAmbiguityFloatUnits

StdevAmbiguityUnits NAV::RealTimeKinematic::_gui_stdevAmbiguityFloatUnits
private

Gui selection for the Unit of the input for the StDev of the ambiguities (while float solution)

Definition at line 192 of file RealTimeKinematic.hpp.

◆ _kalmanFilter

KeyedKalmanFilterD<RTK::States::StateKeyType, RTK::Meas::MeasKeyTypes> NAV::RealTimeKinematic::_kalmanFilter
private

Kalman Filter representation.

Definition at line 252 of file RealTimeKinematic.hpp.

◆ _lastSolutionStatus

RtkSolution::SolutionType NAV::RealTimeKinematic::_lastSolutionStatus
private

Solution type of last epoch.

Definition at line 219 of file RealTimeKinematic.hpp.

◆ _lastUpdate

InsTime NAV::RealTimeKinematic::_lastUpdate
private

Last update time.

Definition at line 247 of file RealTimeKinematic.hpp.

◆ _maxPosVar

double NAV::RealTimeKinematic::_maxPosVar
private

Do not attempt to fix if the position variance is above the threshold.

Definition at line 159 of file RealTimeKinematic.hpp.

◆ _maxPosVarTriggered

bool NAV::RealTimeKinematic::_maxPosVarTriggered
private

Trigger state of the check.

Definition at line 172 of file RealTimeKinematic.hpp.

◆ _maxRemoveOutlier

size_t NAV::RealTimeKinematic::_maxRemoveOutlier
private

Maximum amount of outliers to remove per epoch.

Definition at line 132 of file RealTimeKinematic.hpp.

◆ _maxTimeBetweenBaseRoverForRTK

double NAV::RealTimeKinematic::_maxTimeBetweenBaseRoverForRTK
private

Maximum time between base and rover observations to calculate the RTK solution.

Definition at line 146 of file RealTimeKinematic.hpp.

◆ _nCycleSlipsDual

size_t NAV::RealTimeKinematic::_nCycleSlipsDual
private

Cycle-slip detection count (Dual)

Definition at line 279 of file RealTimeKinematic.hpp.

◆ _nCycleSlipsLLI

size_t NAV::RealTimeKinematic::_nCycleSlipsLLI
private

Cycle-slip detection count (LLI)

Definition at line 277 of file RealTimeKinematic.hpp.

◆ _nCycleSlipsSingle

size_t NAV::RealTimeKinematic::_nCycleSlipsSingle
private

Cycle-slip detection count (Single)

Definition at line 278 of file RealTimeKinematic.hpp.

◆ _nMeasExcludedNIS

size_t NAV::RealTimeKinematic::_nMeasExcludedNIS
private

Measurement excluded due to NIS test count.

Definition at line 280 of file RealTimeKinematic.hpp.

◆ _nMinSatForAmbFix

size_t NAV::RealTimeKinematic::_nMinSatForAmbFix
private

Minimum amount of satellites with carrier observations to try fixing the solution.

Definition at line 155 of file RealTimeKinematic.hpp.

◆ _nMinSatForAmbFixTriggered

bool NAV::RealTimeKinematic::_nMinSatForAmbFixTriggered
private

Trigger state of the check.

Definition at line 174 of file RealTimeKinematic.hpp.

◆ _nMinSatForAmbHold

size_t NAV::RealTimeKinematic::_nMinSatForAmbHold
private

Minimum amount of satellites with carrier observations for holding the ambiguities.

Definition at line 157 of file RealTimeKinematic.hpp.

◆ _nMinSatForAmbHoldTriggered

bool NAV::RealTimeKinematic::_nMinSatForAmbHoldTriggered
private

Trigger state of the check.

Definition at line 175 of file RealTimeKinematic.hpp.

◆ _nPivotChange

size_t NAV::RealTimeKinematic::_nPivotChange
private

Amount of pivot changes performed.

Definition at line 276 of file RealTimeKinematic.hpp.

◆ _obsEstimator

ObservationEstimator NAV::RealTimeKinematic::_obsEstimator
private

Observation Estimator.

Definition at line 130 of file RealTimeKinematic.hpp.

◆ _obsFilter

ObservationFilter NAV::RealTimeKinematic::_obsFilter
private

Observation Filter.

Definition at line 127 of file RealTimeKinematic.hpp.

◆ _outlierMaxPosVarStartup

double NAV::RealTimeKinematic::_outlierMaxPosVarStartup
private

Do not attempt to remove outlier if the position variance is above the threshold in the startup phase [m^2].

Definition at line 141 of file RealTimeKinematic.hpp.

◆ _outlierMaxPosVarStartupTriggered

bool NAV::RealTimeKinematic::_outlierMaxPosVarStartupTriggered
private

Trigger state of the check.

Definition at line 173 of file RealTimeKinematic.hpp.

◆ _outlierMinPsrObsKeep

size_t NAV::RealTimeKinematic::_outlierMinPsrObsKeep
private

Minumum amount of pseudorange observables to leave when doing a NIS check.

Definition at line 138 of file RealTimeKinematic.hpp.

◆ _outlierMinSat

size_t NAV::RealTimeKinematic::_outlierMinSat
private

Minumum amount of satellites for doing a NIS check.

Definition at line 136 of file RealTimeKinematic.hpp.

◆ _outlierRemoveEpochs

size_t NAV::RealTimeKinematic::_outlierRemoveEpochs
private

Amount of epochs to remove an outlier after being found (1 = only current)

Definition at line 134 of file RealTimeKinematic.hpp.

◆ _outputStateEvents

bool NAV::RealTimeKinematic::_outputStateEvents
private

Whether to output state change events.

Definition at line 264 of file RealTimeKinematic.hpp.

◆ _pivotSatellites

unordered_map<std::pair<Code, GnssObs::ObservationType>, PivotSatellite> NAV::RealTimeKinematic::_pivotSatellites
private

Pivot satellites for each constellation.

Definition at line 244 of file RealTimeKinematic.hpp.

◆ _receiver

std::array<Receiver, ReceiverType::ReceiverType_COUNT> NAV::RealTimeKinematic::_receiver
private

Receivers.

Definition at line 213 of file RealTimeKinematic.hpp.

◆ _sppAlgorithm

SPP::Algorithm NAV::RealTimeKinematic::_sppAlgorithm
private

SPP algorithm.

Definition at line 210 of file RealTimeKinematic.hpp.

◆ INPUT_PORT_INDEX_BASE_GNSS_OBS

size_t NAV::RealTimeKinematic::INPUT_PORT_INDEX_BASE_GNSS_OBS
staticconstexprprivate

GnssObs.

Definition at line 98 of file RealTimeKinematic.hpp.

◆ INPUT_PORT_INDEX_BASE_POS

size_t NAV::RealTimeKinematic::INPUT_PORT_INDEX_BASE_POS
staticconstexprprivate

Pos.

Definition at line 97 of file RealTimeKinematic.hpp.

◆ INPUT_PORT_INDEX_GNSS_NAV_INFO

size_t NAV::RealTimeKinematic::INPUT_PORT_INDEX_GNSS_NAV_INFO
staticconstexprprivate

GnssNavInfo.

Definition at line 100 of file RealTimeKinematic.hpp.

◆ INPUT_PORT_INDEX_ROVER_GNSS_OBS

size_t NAV::RealTimeKinematic::INPUT_PORT_INDEX_ROVER_GNSS_OBS
staticconstexprprivate

GnssObs.

Definition at line 99 of file RealTimeKinematic.hpp.

◆ nFixSolutions

size_t NAV::RealTimeKinematic::nFixSolutions
private

Percentage of fix solutions.

Definition at line 270 of file RealTimeKinematic.hpp.

◆ nFloatSolutions

size_t NAV::RealTimeKinematic::nFloatSolutions
private

Percentage of float solutions.

Definition at line 272 of file RealTimeKinematic.hpp.

◆ nSingleSolutions

size_t NAV::RealTimeKinematic::nSingleSolutions
private

Percentage of float solutions.

Definition at line 274 of file RealTimeKinematic.hpp.

◆ OUTPUT_PORT_INDEX_RTKSOL

size_t NAV::RealTimeKinematic::OUTPUT_PORT_INDEX_RTKSOL
staticconstexprprivate

Flow (RtkSol)

Definition at line 102 of file RealTimeKinematic.hpp.


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