![]() |
0.5.0
|
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. | |
RealTimeKinematic & | operator= (const RealTimeKinematic &)=delete |
Copy assignment operator. | |
RealTimeKinematic & | operator= (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. | |
InputPin & | inputPinFromId (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. | |
Node & | operator= (const Node &)=delete |
Copy assignment operator. | |
Node & | operator= (Node &&)=delete |
Move assignment operator. | |
OutputPin & | outputPinFromId (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< RtkSolution > | calcFallbackSppSolution () |
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< OutlierInfo > | removeOutlier (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::PivotChange > | updatePivotSatellite (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< InputPin > | inputPins |
List of input pins. | |
Kind | kind |
Kind of the Node. | |
std::string | name |
Name of the Node. | |
std::vector< OutputPin > | outputPins |
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. |
Numerically integrates Imu data.
Definition at line 52 of file RealTimeKinematic.hpp.
|
private |
Difference storage type.
Definition at line 229 of file RealTimeKinematic.hpp.
|
private |
Definition at line 207 of file RealTimeKinematic.hpp.
enum NAV::RealTimeKinematic::ReceiverType : uint8_t |
Receiver Types.
Enumerator | |
---|---|
Rover | Rover. |
Base | Base. |
ReceiverType_COUNT | Amount of receiver types. |
Definition at line 56 of file RealTimeKinematic.hpp.
|
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.
|
strongprivate |
Possible Units for the Standard deviation of the ambiguities.
Enumerator | |
---|---|
Cycle | [cycle] |
Definition at line 107 of file RealTimeKinematic.hpp.
NAV::RealTimeKinematic::RealTimeKinematic | ( | ) |
Default constructor.
Definition at line 76 of file RealTimeKinematic.cpp.
|
override |
Destructor.
Definition at line 92 of file RealTimeKinematic.cpp.
|
delete |
Copy constructor.
|
delete |
Move constructor.
|
private |
Adds the event to the GUI list.
[in,out] | rtkSol | RtkSolution to update |
[in] | text | Text to display |
Definition at line 670 of file RealTimeKinematic.cpp.
|
private |
Adds or remove Ambiguities to/from the Kalman Filter state depending on the received observations.
[in] | observations | List of GNSS observation data used for the calculation of this epoch |
[in,out] | rtkSol | RtkSolution to update |
Definition at line 1876 of file RealTimeKinematic.cpp.
|
private |
Apply the fixed ambiguities to the kalman filter state.
[in] | fixedAmb | Fixed ambiguities |
[in] | ambKeys | Ambiguity state keys |
[in] | ambMeasKeys | Ambiguity measurement keys |
Definition at line 2737 of file RealTimeKinematic.cpp.
|
private |
Assign the SPP solution to the RTK filter.
sppSol | SPP solution |
Definition at line 795 of file RealTimeKinematic.cpp.
|
nodiscardprivate |
Calculates the double difference of the measurements and estimates.
[in] | observations | List of GNSS observation data used for the calculation of this epoch |
[in] | singleDifferences | List of single differences |
Definition at line 2057 of file RealTimeKinematic.cpp.
|
private |
Calculates a SPP solution as fallback in case no base data is available.
Definition at line 1147 of file RealTimeKinematic.cpp.
|
private |
Calculates the Measurement vector 𝐳, Measurement sensitivity matrix 𝐇 and Measurement noise covariance matrix 𝐑 for the KF update.
[in] | observations | List of GNSS observation data used for the calculation of this epoch |
[in] | doubleDifferences | List of double differences |
[in] | Rtilde | Single observation Measurement Noise Covariance Matrix R for each observation type |
Definition at line 2155 of file RealTimeKinematic.cpp.
|
private |
Calculates the RTK solution.
Definition at line 822 of file RealTimeKinematic.cpp.
|
nodiscardprivate |
Calculates the single difference of the measurements and estimates.
[in] | observations | List of GNSS observation data used for the calculation of this epoch |
Definition at line 2028 of file RealTimeKinematic.cpp.
|
nodiscardprivate |
Calculate the measurement noise matrices for each observation type.
observations | List of GNSS observation data used for the calculation of this epoch |
Definition at line 2112 of file RealTimeKinematic.cpp.
|
staticnodiscard |
String representation of the Class Category.
Definition at line 107 of file RealTimeKinematic.cpp.
|
private |
Checks for cycle-slips.
[in] | observations | List of GNSS observation data used for the calculation of this epoch |
[in,out] | rtkSol | RtkSolution to update |
Definition at line 1254 of file RealTimeKinematic.cpp.
|
overrideprivatevirtual |
Deinitialize the node.
Reimplemented from NAV::Node.
Definition at line 655 of file RealTimeKinematic.cpp.
|
overridevirtual |
ImGui config window which is shown on double click.
Reimplemented from NAV::Node.
Definition at line 112 of file RealTimeKinematic.cpp.
|
overrideprivatevirtual |
Initialize the node.
Reimplemented from NAV::Node.
Definition at line 589 of file RealTimeKinematic.cpp.
|
private |
Does the Kalman Filter prediction.
Definition at line 1203 of file RealTimeKinematic.cpp.
|
private |
Does the Kalman Filter update.
[in,out] | rtkSol | RtkSolution to update |
Definition at line 2487 of file RealTimeKinematic.cpp.
|
delete |
Copy assignment operator.
|
delete |
Move assignment operator.
|
staticprivate |
Function to call to add a new pin.
[in,out] | node | Pointer to this node |
Definition at line 660 of file RealTimeKinematic.cpp.
|
staticprivate |
Function to call to delete a pin.
[in,out] | node | Pointer to this node |
[in] | pinIdx | Input pin index to delete |
Definition at line 665 of file RealTimeKinematic.cpp.
|
private |
Prints the observations for logging.
[in] | observations | List of GNSS observation data used for the calculation of this epoch |
Definition at line 684 of file RealTimeKinematic.cpp.
|
private |
Prints all pivot satellites.
Definition at line 1682 of file RealTimeKinematic.cpp.
|
private |
Receive Function for the Base GNSS Observations.
[in] | queue | Queue with all the received data messages |
[in] | pinIdx | Index of the pin the data is received on |
Definition at line 743 of file RealTimeKinematic.cpp.
|
private |
Receive Function for the Base Position.
[in] | queue | Queue with all the received data messages |
[in] | pinIdx | Index of the pin the data is received on |
Definition at line 721 of file RealTimeKinematic.cpp.
|
private |
Receive Function for the RoverGNSS Observations.
[in] | queue | Queue with all the received data messages |
[in] | pinIdx | Index of the pin the data is received on |
Definition at line 768 of file RealTimeKinematic.cpp.
|
private |
Performs the NIS check.
[in,out] | observations | List of GNSS observation data. Elements can be removed |
[in,out] | rtkSol | RtkSolution to update |
Definition at line 2289 of file RealTimeKinematic.cpp.
|
private |
Removes observations which do not have a second one to do double differences.
[in] | observations | List of GNSS observation data used for the calculation of this epoch |
[in] | filtered | Filtered observations |
[in,out] | rtkSol | RtkSolution to update |
Definition at line 1424 of file RealTimeKinematic.cpp.
|
private |
Resolves the ambiguities in the Kalman filter and updates the state and covariance matrix.
[in] | nCarrierMeasUniqueSatellite | Amount of used |
[in,out] | rtkSol | RtkSolution to update |
Definition at line 2536 of file RealTimeKinematic.cpp.
|
overridevirtual |
Restores the node from a json object.
[in] | j | Json object with the node state |
Reimplemented from NAV::Node.
Definition at line 522 of file RealTimeKinematic.cpp.
|
nodiscardoverridevirtual |
Saves the node into a json object.
Reimplemented from NAV::Node.
Definition at line 480 of file RealTimeKinematic.cpp.
|
nodiscardoverridevirtual |
String representation of the Class Type.
Implements NAV::Node.
Definition at line 102 of file RealTimeKinematic.cpp.
|
staticnodiscard |
String representation of the Class Type.
Definition at line 97 of file RealTimeKinematic.cpp.
|
private |
Adapts the Kalman Filter if a pivot satellite signal was changed.
[in] | newPivotSatSigId | Newly added pivot satellite signal |
[in] | oldPivotSatSigId | Old pivot satellite signal |
[in] | oldPivotObservedInEpoch | Indicates if the old pivot satellite is still observed, or is |
[in,out] | rtkSol | RtkSolution to update |
Definition at line 1745 of file RealTimeKinematic.cpp.
|
private |
Update the specified pivot satellite and also does a pivot change in the Kalman filter state if necessary.
code | Code for the pivot |
obsType | Observation type of the pivot |
observations | List of GNSS observation data used for the calculation of this epoch |
rtkSol | RtkSolution to update |
reason | Reason for changing the pivot |
Definition at line 1486 of file RealTimeKinematic.cpp.
|
private |
Update the pivot satellites for each constellation.
[in] | observations | List of GNSS observation data used for the calculation of this epoch |
[in,out] | rtkSol | RtkSolution to update |
Definition at line 1697 of file RealTimeKinematic.cpp.
|
private |
Measurement noise variance used when fixing ambiguities in [cycles^2] (Value used for calculation)
Definition at line 170 of file RealTimeKinematic.hpp.
|
private |
Ambiguities which are fixed and hold. Values in [cycles].
Definition at line 267 of file RealTimeKinematic.hpp.
|
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.
|
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.
|
private |
Ambiguity resolution algorithms and parameters to use.
Definition at line 149 of file RealTimeKinematic.hpp.
|
private |
Ambiguity resolution strategy.
Definition at line 152 of file RealTimeKinematic.hpp.
|
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.
|
private |
Flag, whether the observation was received this epoch.
Definition at line 216 of file RealTimeKinematic.hpp.
|
private |
Wether to output a SPP solution if no base observations are available.
Definition at line 144 of file RealTimeKinematic.hpp.
|
private |
Cycle-slip detector.
Definition at line 255 of file RealTimeKinematic.hpp.
|
private |
Data interval [s].
Definition at line 249 of file RealTimeKinematic.hpp.
|
private |
Dynamic input pins.
Definition at line 284 of file RealTimeKinematic.hpp.
|
private |
Regex for filtering events.
Definition at line 261 of file RealTimeKinematic.hpp.
|
private |
List of event texts (pivot changes, cycle-slips)
Definition at line 258 of file RealTimeKinematic.hpp.
|
private |
Measurement noise standard deviation used when fixing ambiguities in [cycles] (GUI value)
Definition at line 166 of file RealTimeKinematic.hpp.
|
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.
|
private |
Process noise (standard deviation) for the ambiguities (while fix solution) (Selection in GUI)
Definition at line 201 of file RealTimeKinematic.hpp.
|
private |
Process noise (standard deviation) for the ambiguities (while float solution) (Selection in GUI)
Definition at line 194 of file RealTimeKinematic.hpp.
|
private |
GUI selection for the Standard deviation of the acceleration 𝜎_a due to user motion in horizontal and vertical component.
Definition at line 189 of file RealTimeKinematic.hpp.
|
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.
|
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.
|
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.
|
private |
Kalman Filter representation.
Definition at line 252 of file RealTimeKinematic.hpp.
|
private |
Solution type of last epoch.
Definition at line 219 of file RealTimeKinematic.hpp.
|
private |
Last update time.
Definition at line 247 of file RealTimeKinematic.hpp.
|
private |
Do not attempt to fix if the position variance is above the threshold.
Definition at line 159 of file RealTimeKinematic.hpp.
|
private |
Trigger state of the check.
Definition at line 172 of file RealTimeKinematic.hpp.
|
private |
Maximum amount of outliers to remove per epoch.
Definition at line 132 of file RealTimeKinematic.hpp.
|
private |
Maximum time between base and rover observations to calculate the RTK solution.
Definition at line 146 of file RealTimeKinematic.hpp.
|
private |
Cycle-slip detection count (Dual)
Definition at line 279 of file RealTimeKinematic.hpp.
|
private |
Cycle-slip detection count (LLI)
Definition at line 277 of file RealTimeKinematic.hpp.
|
private |
Cycle-slip detection count (Single)
Definition at line 278 of file RealTimeKinematic.hpp.
|
private |
Measurement excluded due to NIS test count.
Definition at line 280 of file RealTimeKinematic.hpp.
|
private |
Minimum amount of satellites with carrier observations to try fixing the solution.
Definition at line 155 of file RealTimeKinematic.hpp.
|
private |
Trigger state of the check.
Definition at line 174 of file RealTimeKinematic.hpp.
|
private |
Minimum amount of satellites with carrier observations for holding the ambiguities.
Definition at line 157 of file RealTimeKinematic.hpp.
|
private |
Trigger state of the check.
Definition at line 175 of file RealTimeKinematic.hpp.
|
private |
Amount of pivot changes performed.
Definition at line 276 of file RealTimeKinematic.hpp.
|
private |
Observation Estimator.
Definition at line 130 of file RealTimeKinematic.hpp.
|
private |
Observation Filter.
Definition at line 127 of file RealTimeKinematic.hpp.
|
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.
|
private |
Trigger state of the check.
Definition at line 173 of file RealTimeKinematic.hpp.
|
private |
Minumum amount of pseudorange observables to leave when doing a NIS check.
Definition at line 138 of file RealTimeKinematic.hpp.
|
private |
Minumum amount of satellites for doing a NIS check.
Definition at line 136 of file RealTimeKinematic.hpp.
|
private |
Amount of epochs to remove an outlier after being found (1 = only current)
Definition at line 134 of file RealTimeKinematic.hpp.
|
private |
Whether to output state change events.
Definition at line 264 of file RealTimeKinematic.hpp.
|
private |
Pivot satellites for each constellation.
Definition at line 244 of file RealTimeKinematic.hpp.
|
private |
Receivers.
Definition at line 213 of file RealTimeKinematic.hpp.
|
private |
SPP algorithm.
Definition at line 210 of file RealTimeKinematic.hpp.
|
staticconstexprprivate |
Definition at line 98 of file RealTimeKinematic.hpp.
|
staticconstexprprivate |
Pos.
Definition at line 97 of file RealTimeKinematic.hpp.
|
staticconstexprprivate |
Definition at line 100 of file RealTimeKinematic.hpp.
|
staticconstexprprivate |
Definition at line 99 of file RealTimeKinematic.hpp.
|
private |
Percentage of fix solutions.
Definition at line 270 of file RealTimeKinematic.hpp.
|
private |
Percentage of float solutions.
Definition at line 272 of file RealTimeKinematic.hpp.
|
private |
Percentage of float solutions.
Definition at line 274 of file RealTimeKinematic.hpp.
|
staticconstexprprivate |
Flow (RtkSol)
Definition at line 102 of file RealTimeKinematic.hpp.