0.3.0
Loading...
Searching...
No Matches
NAV::PosVelAttInitializer Class Reference

Position, Velocity, Attitude Initializer from GPS and IMU data. More...

Public Member Functions

void guiConfig () override
 ImGui config window which is shown on double click.
 
PosVelAttInitializeroperator= (const PosVelAttInitializer &)=delete
 Copy assignment operator.
 
PosVelAttInitializeroperator= (PosVelAttInitializer &&)=delete
 Move assignment operator.
 
 PosVelAttInitializer ()
 Default constructor.
 
 PosVelAttInitializer (const PosVelAttInitializer &)=delete
 Copy constructor.
 
 PosVelAttInitializer (PosVelAttInitializer &&)=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.
 
 ~PosVelAttInitializer () 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.
 
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

enum class  AttitudeMode : uint8_t {
  BOTH ,
  IMU ,
  GNSS ,
  COUNT
}
 Initialization source for attitude. More...
 
enum class  VelocityOverride : uint8_t {
  OFF ,
  ECEF ,
  NED ,
  COUNT
}
 Override options for Position. More...
 

Private Member Functions

void deinitialize () override
 Deinitialize the node.
 
void finalizeInit ()
 Checks whether all Flags are set and writes logs messages.
 
bool initialize () override
 Initialize the node.
 
std::shared_ptr< const NodeDatapollPVASolution ()
 Polls the PVA solution if all is set in the GUI.
 
void receiveGnssObs (InputPin::NodeDataQueue &queue, size_t pinIdx)
 Receive Gnss Observations.
 
void receiveImuObs (InputPin::NodeDataQueue &queue, size_t pinIdx)
 Receive Imu Observations.
 
void receivePosObs (const std::shared_ptr< const Pos > &obs)
 Receive Pos Observations.
 
void receivePosVelAttObs (const std::shared_ptr< const PosVelAtt > &obs)
 Receive PosVelAtt Observations.
 
void receivePosVelObs (const std::shared_ptr< const PosVel > &obs)
 Receive PosVel Observations.
 
void receiveUbloxObs (const std::shared_ptr< const UbloxObs > &obs)
 Receive Ublox Observations.
 
void updatePins ()
 Add or removes input pins depending on the settings and modifies the output pin.
 

Private Attributes

AttitudeMode _attitudeMode
 GUI option to pecify the initialization source for attitude.
 
std::array< double, 3 > _averagedAttitude
 Averaged Attitude (roll, pitch, yaw) in [rad].
 
double _countAveragedAttitude
 Count of received attitude measurements.
 
Eigen::Vector3d _e_initPosition
 Position in ECEF coordinates.
 
double _initDuration
 Time in [s] to initialize the state.
 
InsTime _initTime
 Initialization time.
 
gui::widgets::TimeEditFormat _initTimeEditFormat
 Time Format to input the init time with.
 
int _inputPinIdxGNSS
 Index of the input pin for GNSS observations.
 
int _inputPinIdxIMU
 Index of the input pin for IMU observations.
 
std::array< double, 3 > _lastPositionAccuracy
 Last position accuracy in [cm] for XYZ or NED.
 
std::array< double, 3 > _lastVelocityAccuracy
 Last velocity accuracy in [cm/s] for XYZ or NED.
 
Eigen::Vector3d _n_initVelocity
 Velocity in navigation coordinates.
 
Eigen::Quaterniond _n_Quat_b_init
 Initialized Quaternion body to navigation frame (roll, pitch, yaw)
 
bool _overridePosition
 Whether the GNSS values should be used or we want to override the values manually.
 
gui::widgets::PositionWithFrame _overridePositionValue
 Values to override the Position in ECEF coordinates in [m].
 
std::array< bool, 3 > _overrideRollPitchYaw
 Whether the IMU values should be used or we want to override the values manually.
 
std::array< double, 3 > _overrideRollPitchYawValues
 Values to override Roll, Pitch and Yaw with in [deg].
 
VelocityOverride _overrideVelocity
 Whether the GNSS values should be used or we want to override the values manually.
 
Eigen::Vector3d _overrideVelocityValues
 Values to override the Velocity in [m/s].
 
double _positionAccuracyThreshold
 Position Accuracy to achieve in [cm].
 
std::array< bool, 4 > _posVelAttInitialized
 Whether the states are initialized (pos, vel, att, messages send)
 
uint64_t _startTime
 Start time of the averageing process.
 
double _velocityAccuracyThreshold
 Velocity Accuracy to achieve in [cm/s].
 

Static Private Attributes

static constexpr size_t OUTPUT_PORT_INDEX_POS_VEL_ATT
 Flow (PosVelAtt)
 

Friends

constexpr const char * to_string (PosVelAttInitializer::AttitudeMode attitudeMode)
 Converts the enum to a string.
 
constexpr const char * to_string (PosVelAttInitializer::VelocityOverride velOverride)
 Converts the enum to a string.
 

Additional Inherited Members

- 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 Attributes 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

Position, Velocity, Attitude Initializer from GPS and IMU data.

Member Enumeration Documentation

◆ AttitudeMode

enum class NAV::PosVelAttInitializer::AttitudeMode : uint8_t
strongprivate

Initialization source for attitude.

Enumerator
BOTH 

Use IMU and GNSS Observations for attitude initialization.

IMU 

Use IMU Observations for attitude initialization.

GNSS 

Use GNSS Observations for attitude initialization.

COUNT 

Amount of items in the enum.

◆ VelocityOverride

enum class NAV::PosVelAttInitializer::VelocityOverride : uint8_t
strongprivate

Override options for Position.

Enumerator
OFF 

Do not override the values.

ECEF 

Override with ECEF values.

NED 

Override with NED values.

COUNT 

Amount of items in the enum.

Member Function Documentation

◆ deinitialize()

void NAV::PosVelAttInitializer::deinitialize ( )
overrideprivatevirtual

Deinitialize the node.

Reimplemented from NAV::Node.

◆ guiConfig()

void NAV::PosVelAttInitializer::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.

◆ initialize()

bool NAV::PosVelAttInitializer::initialize ( )
overrideprivatevirtual

Initialize the node.

Reimplemented from NAV::Node.

◆ pollPVASolution()

std::shared_ptr< const NodeData > NAV::PosVelAttInitializer::pollPVASolution ( )
nodiscardprivate

Polls the PVA solution if all is set in the GUI.

Returns
The PVA solution

◆ receiveGnssObs()

void NAV::PosVelAttInitializer::receiveGnssObs ( InputPin::NodeDataQueue & queue,
size_t pinIdx )
private

Receive Gnss Observations.

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

◆ receiveImuObs()

void NAV::PosVelAttInitializer::receiveImuObs ( InputPin::NodeDataQueue & queue,
size_t pinIdx )
private

Receive Imu Observations.

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

◆ receivePosObs()

void NAV::PosVelAttInitializer::receivePosObs ( const std::shared_ptr< const Pos > & obs)
private

Receive Pos Observations.

Parameters
[in]obsPos Data

◆ receivePosVelAttObs()

void NAV::PosVelAttInitializer::receivePosVelAttObs ( const std::shared_ptr< const PosVelAtt > & obs)
private

Receive PosVelAtt Observations.

Parameters
[in]obsPosVelAtt Data

◆ receivePosVelObs()

void NAV::PosVelAttInitializer::receivePosVelObs ( const std::shared_ptr< const PosVel > & obs)
private

Receive PosVel Observations.

Parameters
[in]obsPosVel Data

◆ receiveUbloxObs()

void NAV::PosVelAttInitializer::receiveUbloxObs ( const std::shared_ptr< const UbloxObs > & obs)
private

Receive Ublox Observations.

Parameters
[in]obsUblox Data

◆ restore()

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

Restores the node from a json object.

Parameters
[in]jJson object with the node state

Reimplemented from NAV::Node.

◆ save()

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

Saves the node into a json object.

Reimplemented from NAV::Node.

◆ type()

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

String representation of the Class Type.

Implements NAV::Node.

Friends And Related Symbol Documentation

◆ to_string [1/2]

const char * to_string ( PosVelAttInitializer::AttitudeMode attitudeMode)
friend

Converts the enum to a string.

Parameters
[in]attitudeModeEnum value to convert into text
Returns
String representation of the enum

◆ to_string [2/2]

const char * to_string ( PosVelAttInitializer::VelocityOverride velOverride)
friend

Converts the enum to a string.

Parameters
[in]velOverrideEnum value to convert into text
Returns
String representation of the enum

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