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

Imu Observation Simulator. More...

Public Member Functions

void guiConfig () override
 ImGui config window which is shown on double click.
 
 ImuSimulator ()
 Default constructor.
 
 ImuSimulator (const ImuSimulator &)=delete
 Copy constructor.
 
 ImuSimulator (ImuSimulator &&)=delete
 Move constructor.
 
ImuSimulatoroperator= (const ImuSimulator &)=delete
 Copy assignment operator.
 
ImuSimulatoroperator= (ImuSimulator &&)=delete
 Move assignment operator.
 
bool resetNode () override
 Resets the node. Moves the read cursor to the start.
 
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.
 
 ~ImuSimulator () override
 Destructor.
 
- Public Member Functions inherited from NAV::Imu
 Imu (const Imu &)=delete
 Copy constructor.
 
 Imu (Imu &&)=delete
 Move constructor.
 
const ImuPosimuPosition () const
 Position and rotation information for conversion from platform to body frame.
 
Imuoperator= (const Imu &)=delete
 Copy assignment operator.
 
Imuoperator= (Imu &&)=delete
 Move assignment operator.
 
 ~Imu () override=default
 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 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  Direction : uint8_t {
  CW ,
  CCW ,
  COUNT
}
 Possible directions for the circular trajectory. More...
 
enum class  StartTimeSource : uint8_t {
  CustomTime ,
  CurrentComputerTime
}
 Types where the start time should be pulled from. More...
 
enum  StopCondition : uint8_t {
  Duration ,
  DistanceOrCirclesOrRoses
}
 Possible stop conditions for the simulation. More...
 
enum class  TrajectoryType : uint8_t {
  Fixed ,
  Linear ,
  Circular ,
  Csv ,
  RoseFigure ,
  COUNT
}
 Types of Trajectories available for simulation. More...
 

Private Member Functions

std::array< double, 3 > calcFlightAngles (double time) const
 Calculates the flight angles (roll, pitch, yaw)
 
bool checkStopCondition (double time, const Eigen::Vector3d &lla_position)
 Checks the selected stop condition.
 
void deinitialize () override
 Deinitialize the node.
 
Eigen::Vector3d e_getPositionFromCsvLine (const CsvData::CsvLine &line, const std::vector< std::string > &description) const
 Get the Position from a CSV line.
 
InsTime getTimeFromCsvLine (const CsvData::CsvLine &line, const std::vector< std::string > &description) const
 Get the Time from a CSV line.
 
bool initialize () override
 Initialize the node.
 
bool initializeSplines ()
 Initializes the spline values.
 
Eigen::Vector3d lla_calcPosition (double time) const
 Calculates the position in latLonAlt at the given time depending on the trajectoryType.
 
Eigen::Vector3d n_calcOmega_nb (double time, const Eigen::Vector3d &rollPitchYaw, const Eigen::Quaterniond &n_Quat_b) const
 Calculates ω_nb_n, the turn rate of the body with respect to the navigation system expressed in NED coordinates.
 
Eigen::Vector3d n_calcTrajectoryAccel (double time, const Eigen::Quaterniond &n_Quat_e, const Eigen::Vector3d &lla_position, const Eigen::Vector3d &n_velocity) const
 Calculates the acceleration in local-navigation frame coordinates at the given time depending on the trajectoryType.
 
Eigen::Vector3d n_calcVelocity (double time, const Eigen::Quaterniond &n_Quat_e) const
 Calculates the velocity in local-navigation frame coordinates at the given time depending on the trajectoryType.
 
std::shared_ptr< const NodeDatapollImuObs (size_t pinIdx, bool peek)
 Polls the next simulated data.
 
std::shared_ptr< const NodeDatapollPosVelAtt (size_t pinIdx, bool peek)
 Polls the next simulated data.
 

Static Private Member Functions

static Eigen::Quaterniond n_getAttitudeQuaternionFromCsvLine_b (const CsvData::CsvLine &line, const std::vector< std::string > &description)
 Get the Attitude quaternion n_quat_b from a CSV line.
 
static const char * to_string (Direction value)
 Converts the enum to a string.
 
static const char * to_string (TrajectoryType value)
 Converts the enum to a string.
 

Private Attributes

bool _angularRateEarthRotationEnabled
 Apply the Earth rotation rate to the measured angular rates.
 
bool _angularRateTransportRateEnabled
 Apply the transport rate to the measured angular rates.
 
bool _centrifgalAccelerationEnabled
 Apply the centrifugal acceleration to the measured accelerations.
 
double _circularHarmonicAmplitudeFactor
 Harmonic Oscillation Amplitude Factor of the circle radius [-].
 
int _circularHarmonicFrequency
 Harmonic Oscillation Frequency on the circular trajectory [cycles/revolution].
 
double _circularTrajectoryCircleCountForStop
 Amount of circles to simulate before stopping.
 
bool _coriolisAccelerationEnabled
 Apply the coriolis acceleration to the measured accelerations.
 
double _csvDuration
 Duration from the CSV file in [s].
 
Eigen::Vector3d _fixedTrajectoryStartOrientation
 Orientation of the vehicle [roll, pitch, yaw] [rad].
 
double _gnssFrequency
 Frequency to sample the position with in [Hz].
 
double _gnssLastUpdateTime
 Last time the GNSS message was calculated in [s].
 
uint64_t _gnssUpdateCnt
 Counter to calculate the GNSS update time.
 
GravitationModel _gravitationModel
 Gravitation model selected in the GUI.
 
double _imuFrequency
 Frequency to sample the IMU with in [Hz].
 
double _imuInternalFrequency
 Frequency to calculate the delta IMU values in [Hz].
 
uint64_t _imuInternalUpdateCnt
 Counter to calculate the internal IMU update time.
 
double _imuLastUpdateTime
 Last time the IMU message was calculated in [s].
 
uint64_t _imuUpdateCnt
 Counter to calculate the IMU update time.
 
double _linearTrajectoryDistanceForStop
 Distance in [m] to the start position to stop the simulation.
 
Eigen::Vector3d _lla_gnssLastLinearPosition
 Last calculated position for the GNSS in linear mode for iterative calculations as latitude, longitude, altitude [rad, rad, m].
 
Eigen::Vector3d _lla_imuLastLinearPosition
 Last calculated position for the IMU in linear mode for iterative calculations as latitude, longitude, altitude [rad, rad, m].
 
Eigen::Vector3d _n_linearTrajectoryStartVelocity
 Start Velocity of the vehicle in local-navigation frame cooridnates in [m/s].
 
Eigen::Vector3d _p_lastImuAccelerationMeas
 Last calculated acceleration measurement in platform coordinates [m/s²].
 
Eigen::Vector3d _p_lastImuAngularRateMeas
 Last calculated angular rate measurement in platform coordinates [rad/s].
 
int _rosePetDenom
 In the GUI selected denominator of petals (2*k for even k, k for uneven k) of the rose figure.
 
int _rosePetNum
 In the GUI selected numerator of petals (2*k for even k, k for uneven k) of the rose figure.
 
double _roseSimDuration
 Simulation duration needed for the rose figure.
 
double _roseStepLengthMax
 Maxmimum step length for the spline points for the rose figure [m]. Points will be spaced between [L/3 L].
 
double _roseTrajectoryCountForStop
 Amount of rose figures to simulate before stopping.
 
double _simulationDuration
 Duration to simulate in [s].
 
StopCondition _simulationStopCondition
 Condition which has to be met to stop the simulation.
 
struct { 
 
   CubicSpline< long double >   pitch 
 Pitch angle [rad].
 
   CubicSpline< long double >   roll 
 Roll angle [rad].
 
   double   sampleInterval 
 Spline sample interval.
 
   CubicSpline< long double >   x 
 ECEF X Position [m].
 
   CubicSpline< long double >   y 
 ECEF Y Position [m].
 
   CubicSpline< long double >   yaw 
 Yaw angle [rad].
 
   CubicSpline< long double >   z 
 ECEF Z Position [m].
 
_splines 
 Assign a variable that holds the Spline information.
 
gui::widgets::PositionWithFrame _startPosition
 
InsTime _startTime
 Global starttime.
 
gui::widgets::TimeEditFormat _startTimeEditFormat
 Time Format to input the start time with.
 
StartTimeSource _startTimeSource
 Source for the start time, selected in the GUI.
 
Direction _trajectoryDirection
 In the GUI selected direction of the circular trajectory (used by circular and rose figure)
 
double _trajectoryHorizontalSpeed
 Horizontal speed of the vehicle in the tangential plane in [m/s] (used by circular and rose figure)
 
double _trajectoryRadius
 In the GUI selected radius of the circular trajectory (used by circular and rose figure)
 
double _trajectoryRotationAngle
 In the GUI selected origin angle of the circular trajectory in [rad].
 
TrajectoryType _trajectoryType
 Selected trajectory type in the GUI.
 
double _trajectoryVerticalSpeed
 Vertical speed of the vehicle in the tangential plane in [m/s] (used by circular and rose figure)
 

Static Private Attributes

static constexpr size_t INPUT_PORT_INDEX_CSV
 Object (CsvData)
 
static constexpr double INTERNAL_LINEAR_UPDATE_FREQUENCY
 Update rate for the internal solution of linear movement in [Hz].
 
static constexpr size_t OUTPUT_PORT_INDEX_IMU_OBS
 Flow (ImuObs)
 
static constexpr size_t OUTPUT_PORT_INDEX_POS_VEL_ATT
 Flow (PosVelAtt)
 

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 Member Functions inherited from NAV::Imu
 Imu (std::string name)
 Constructor.
 
- Protected Attributes inherited from NAV::Imu
ImuPos _imuPos
 Position and rotation information for conversion from platform to body frame.
 
- 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

Imu Observation Simulator.

Member Enumeration Documentation

◆ Direction

enum class NAV::ImuSimulator::Direction : uint8_t
strongprivate

Possible directions for the circular trajectory.

Enumerator
CW 

Clockwise.

CCW 

Counterclockwise.

COUNT 

Amount of items in the enum.

◆ StartTimeSource

enum class NAV::ImuSimulator::StartTimeSource : uint8_t
strongprivate

Types where the start time should be pulled from.

Enumerator
CustomTime 

Custom time selected by the user.

CurrentComputerTime 

Gets the current computer time as start time.

◆ StopCondition

enum NAV::ImuSimulator::StopCondition : uint8_t
private

Possible stop conditions for the simulation.

Enumerator
Duration 

Time Duration.

DistanceOrCirclesOrRoses 

Distance for Linear trajectory / Circle count for Circular / Count for rose figure trajectory.

◆ TrajectoryType

enum class NAV::ImuSimulator::TrajectoryType : uint8_t
strongprivate

Types of Trajectories available for simulation.

Enumerator
Fixed 

Static position without movement.

Linear 

Linear movement with constant velocity.

Circular 

Circular path.

Csv 

Get the input from the CsvData pin.

RoseFigure 

Movement along a mathmatical rose figure.

COUNT 

Amount of items in the enum.

Member Function Documentation

◆ calcFlightAngles()

std::array< double, 3 > NAV::ImuSimulator::calcFlightAngles ( double time) const
nodiscardprivate

Calculates the flight angles (roll, pitch, yaw)

Parameters
[in]timeTime in [s]
Returns
Roll, pitch, yaw in [rad]

◆ checkStopCondition()

bool NAV::ImuSimulator::checkStopCondition ( double time,
const Eigen::Vector3d & lla_position )
private

Checks the selected stop condition.

Parameters
[in]timeCurrent simulation time
[in]lla_positionCurrent position
Returns
True if it should be stopped

◆ deinitialize()

void NAV::ImuSimulator::deinitialize ( )
overrideprivatevirtual

Deinitialize the node.

Reimplemented from NAV::Node.

◆ e_getPositionFromCsvLine()

Eigen::Vector3d NAV::ImuSimulator::e_getPositionFromCsvLine ( const CsvData::CsvLine & line,
const std::vector< std::string > & description ) const
nodiscardprivate

Get the Position from a CSV line.

Parameters
[in]lineLine with data from the csv
[in]descriptionDescription of the data
Returns
Position in ECEF coordinates in [m] or NaN if data not found

◆ getTimeFromCsvLine()

InsTime NAV::ImuSimulator::getTimeFromCsvLine ( const CsvData::CsvLine & line,
const std::vector< std::string > & description ) const
nodiscardprivate

Get the Time from a CSV line.

Parameters
[in]lineLine with data from the csv
[in]descriptionDescription of the data
Returns
InsTime or empty time if data not found

◆ guiConfig()

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

◆ initialize()

bool NAV::ImuSimulator::initialize ( )
overrideprivatevirtual

Initialize the node.

Reimplemented from NAV::Node.

◆ initializeSplines()

bool NAV::ImuSimulator::initializeSplines ( )
private

Initializes the spline values.

Returns
True if everything succeeded

◆ lla_calcPosition()

Eigen::Vector3d NAV::ImuSimulator::lla_calcPosition ( double time) const
nodiscardprivate

Calculates the position in latLonAlt at the given time depending on the trajectoryType.

Parameters
[in]timeTime in [s]
Returns
LatLonAlt in [rad, rad, m]

◆ n_calcOmega_nb()

Eigen::Vector3d NAV::ImuSimulator::n_calcOmega_nb ( double time,
const Eigen::Vector3d & rollPitchYaw,
const Eigen::Quaterniond & n_Quat_b ) const
nodiscardprivate

Calculates ω_nb_n, the turn rate of the body with respect to the navigation system expressed in NED coordinates.

Parameters
[in]timeTime in [s]
[in]rollPitchYawGimbal angles (roll, pitch, yaw) [rad]
[in]n_Quat_bRotation quaternion from body frame to the local-navigation frame
Returns
ω_nb_n [rad/s]

◆ n_calcTrajectoryAccel()

Eigen::Vector3d NAV::ImuSimulator::n_calcTrajectoryAccel ( double time,
const Eigen::Quaterniond & n_Quat_e,
const Eigen::Vector3d & lla_position,
const Eigen::Vector3d & n_velocity ) const
nodiscardprivate

Calculates the acceleration in local-navigation frame coordinates at the given time depending on the trajectoryType.

Parameters
[in]timeTime in [s]
[in]n_Quat_eRotation quaternion from Earth frame to local-navigation frame
[in]lla_positionCurrent position as latitude, longitude, altitude [rad, rad, m]
[in]n_velocityVelocity in local-navigation frame coordinates [m/s]
Returns
n_accel in [rad, rad, m]

◆ n_calcVelocity()

Eigen::Vector3d NAV::ImuSimulator::n_calcVelocity ( double time,
const Eigen::Quaterniond & n_Quat_e ) const
nodiscardprivate

Calculates the velocity in local-navigation frame coordinates at the given time depending on the trajectoryType.

Parameters
[in]timeTime in [s]
[in]n_Quat_eRotation quaternion from Earth frame to local-navigation frame
Returns
n_velocity in [rad, rad, m]

◆ n_getAttitudeQuaternionFromCsvLine_b()

static Eigen::Quaterniond NAV::ImuSimulator::n_getAttitudeQuaternionFromCsvLine_b ( const CsvData::CsvLine & line,
const std::vector< std::string > & description )
staticprivate

Get the Attitude quaternion n_quat_b from a CSV line.

Parameters
[in]lineLine with data from the csv
[in]descriptionDescription of the data
Returns
Attitude quaternion n_quat_b or NaN if data not found

◆ pollImuObs()

std::shared_ptr< const NodeData > NAV::ImuSimulator::pollImuObs ( size_t pinIdx,
bool peek )
nodiscardprivate

Polls the next simulated data.

Parameters
[in]pinIdxIndex of the pin the data is requested on
[in]peekSpecifies if the data should be peeked or read
Returns
The simulated observation

◆ pollPosVelAtt()

std::shared_ptr< const NodeData > NAV::ImuSimulator::pollPosVelAtt ( size_t pinIdx,
bool peek )
nodiscardprivate

Polls the next simulated data.

Parameters
[in]pinIdxIndex of the pin the data is requested on
[in]peekSpecifies if the data should be peeked or read
Returns
The simulated observation

◆ resetNode()

bool NAV::ImuSimulator::resetNode ( )
overridevirtual

Resets the node. Moves the read cursor to the start.

Reimplemented from NAV::Node.

◆ restore()

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

Restores the node from a json object.

Parameters
[in]jJson object with the node state

Reimplemented from NAV::Imu.

◆ save()

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

Saves the node into a json object.

Reimplemented from NAV::Imu.

◆ to_string() [1/2]

static const char * NAV::ImuSimulator::to_string ( Direction value)
staticprivate

Converts the enum to a string.

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

◆ to_string() [2/2]

static const char * NAV::ImuSimulator::to_string ( TrajectoryType value)
staticprivate

Converts the enum to a string.

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

◆ type()

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

String representation of the Class Type.

Implements NAV::Node.

Member Data Documentation

◆ _startPosition

gui::widgets::PositionWithFrame NAV::ImuSimulator::_startPosition
private

Start position in local navigation coordinates (latitude, longitude, altitude) [rad, rad, m]

  • Fixed, Linear: Start position
  • Circular: Center of the circle

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