![]()  | 
              
                  0.5.0
                 
               | 
            
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.   | |
| ImuSimulator & | operator= (const ImuSimulator &)=delete | 
| Copy assignment operator.   | |
| ImuSimulator & | operator= (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 ImuPos & | imuPosition () const | 
| Position and rotation information for conversion from platform to body frame.   | |
| Imu & | operator= (const Imu &)=delete | 
| Copy assignment operator.   | |
| Imu & | operator= (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.   | |
| 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 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.   | |
| std::optional< Eigen::Vector3d > | e_getPositionFromCsvLine (const CsvData::CsvLine &line, const std::vector< std::string > &description) const | 
| Get the Position from a CSV line.   | |
| std::optional< 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::optional< Eigen::Quaterniond > | n_getAttitudeQuaternionFromCsvLine_b (const CsvData::CsvLine &line, const std::vector< std::string > &description) const | 
| Get the Attitude quaternion n_quat_b from a CSV line.   | |
| std::shared_ptr< const NodeData > | pollImuObs (size_t pinIdx, bool peek) | 
| Polls the next simulated data.   | |
| std::shared_ptr< const NodeData > | pollPosVelAtt (size_t pinIdx, bool peek) | 
| Polls the next simulated data.   | |
Static Private Member Functions | |
| 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].  More... | |
| CubicSpline< long double > roll | |
| Roll angle [rad].  More... | |
| double sampleInterval | |
| Spline sample interval.  More... | |
| CubicSpline< long double > x | |
| ECEF X Position [m].  More... | |
| CubicSpline< long double > y | |
| ECEF Y Position [m].  More... | |
| CubicSpline< long double > yaw | |
| Yaw angle [rad].  More... | |
| CubicSpline< long double > z | |
| ECEF Z Position [m].  More... | |
| } | _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... | |
| 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 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.   | |
Imu Observation Simulator.
Definition at line 33 of file ImuSimulator.hpp.
      
  | 
  strongprivate | 
Possible directions for the circular trajectory.
| Enumerator | |
|---|---|
| CW | Clockwise.  | 
| CCW | Counterclockwise.  | 
| COUNT | Amount of items in the enum.  | 
Definition at line 167 of file ImuSimulator.hpp.
      
  | 
  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.  | 
Definition at line 104 of file ImuSimulator.hpp.
      
  | 
  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.  | 
Definition at line 208 of file ImuSimulator.hpp.
      
  | 
  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.  | 
Definition at line 131 of file ImuSimulator.hpp.
| NAV::ImuSimulator::ImuSimulator | ( | ) | 
Default constructor.
Definition at line 36 of file ImuSimulator.cpp.
      
  | 
  override | 
Destructor.
Definition at line 48 of file ImuSimulator.cpp.
      
  | 
  delete | 
Copy constructor.
      
  | 
  delete | 
Move constructor.
      
  | 
  nodiscardprivate | 
Calculates the flight angles (roll, pitch, yaw)
| [in] | time | Time in [s] | 
Definition at line 1726 of file ImuSimulator.cpp.
      
  | 
  staticnodiscard | 
String representation of the Class Category.
Definition at line 63 of file ImuSimulator.cpp.
      
  | 
  private | 
Checks the selected stop condition.
| [in] | time | Current simulation time | 
| [in] | lla_position | Current position | 
Definition at line 1503 of file ImuSimulator.cpp.
      
  | 
  overrideprivatevirtual | 
Deinitialize the node.
Reimplemented from NAV::Node.
Definition at line 1451 of file ImuSimulator.cpp.
      
  | 
  nodiscardprivate | 
Get the Position from a CSV line.
| [in] | line | Line with data from the csv | 
| [in] | description | Description of the data | 
Definition at line 892 of file ImuSimulator.cpp.
      
  | 
  nodiscardprivate | 
Get the Time from a CSV line.
| [in] | line | Line with data from the csv | 
| [in] | description | Description of the data | 
Definition at line 846 of file ImuSimulator.cpp.
      
  | 
  overridevirtual | 
ImGui config window which is shown on double click.
Reimplemented from NAV::Imu.
Definition at line 68 of file ImuSimulator.cpp.
      
  | 
  overrideprivatevirtual | 
Initialize the node.
Reimplemented from NAV::Node.
Definition at line 1444 of file ImuSimulator.cpp.
      
  | 
  private | 
Initializes the spline values.
Definition at line 966 of file ImuSimulator.cpp.
      
  | 
  nodiscardprivate | 
Calculates the position in latLonAlt at the given time depending on the trajectoryType.
| [in] | time | Time in [s] | 
Definition at line 1735 of file ImuSimulator.cpp.
      
  | 
  nodiscardprivate | 
Calculates ω_nb_n, the turn rate of the body with respect to the navigation system expressed in NED coordinates.
| [in] | time | Time in [s] | 
| [in] | rollPitchYaw | Gimbal angles (roll, pitch, yaw) [rad] | 
| [in] | n_Quat_b | Rotation quaternion from body frame to the local-navigation frame | 
Definition at line 1775 of file ImuSimulator.cpp.
      
  | 
  nodiscardprivate | 
Calculates the acceleration in local-navigation frame coordinates at the given time depending on the trajectoryType.
| [in] | time | Time in [s] | 
| [in] | n_Quat_e | Rotation quaternion from Earth frame to local-navigation frame | 
| [in] | lla_position | Current position as latitude, longitude, altitude [rad, rad, m] | 
| [in] | n_velocity | Velocity in local-navigation frame coordinates [m/s] | 
Definition at line 1751 of file ImuSimulator.cpp.
      
  | 
  nodiscardprivate | 
Calculates the velocity in local-navigation frame coordinates at the given time depending on the trajectoryType.
| [in] | time | Time in [s] | 
| [in] | n_Quat_e | Rotation quaternion from Earth frame to local-navigation frame | 
Definition at line 1743 of file ImuSimulator.cpp.
      
  | 
  nodiscardprivate | 
Get the Attitude quaternion n_quat_b from a CSV line.
| [in] | line | Line with data from the csv | 
| [in] | description | Description of the data | 
Definition at line 928 of file ImuSimulator.cpp.
      
  | 
  delete | 
Copy assignment operator.
      
  | 
  delete | 
Move assignment operator.
      
  | 
  nodiscardprivate | 
Polls the next simulated data.
| [in] | pinIdx | Index of the pin the data is requested on | 
| [in] | peek | Specifies if the data should be peeked or read | 
Definition at line 1537 of file ImuSimulator.cpp.
      
  | 
  nodiscardprivate | 
Polls the next simulated data.
| [in] | pinIdx | Index of the pin the data is requested on | 
| [in] | peek | Specifies if the data should be peeked or read | 
Definition at line 1685 of file ImuSimulator.cpp.
      
  | 
  overridevirtual | 
Resets the node. Moves the read cursor to the start.
Reimplemented from NAV::Node.
Definition at line 1456 of file ImuSimulator.cpp.
      
  | 
  overridevirtual | 
Restores the node from a json object.
| [in] | j | Json object with the node state | 
Reimplemented from NAV::Imu.
Definition at line 698 of file ImuSimulator.cpp.
      
  | 
  nodiscardoverridevirtual | 
Saves the node into a json object.
Reimplemented from NAV::Imu.
Definition at line 651 of file ImuSimulator.cpp.
      
  | 
  staticprivate | 
Converts the enum to a string.
| [in] | value | Enum value to convert into text | 
Definition at line 1833 of file ImuSimulator.cpp.
      
  | 
  staticprivate | 
Converts the enum to a string.
| [in] | value | Enum value to convert into text | 
Definition at line 1813 of file ImuSimulator.cpp.
      
  | 
  nodiscardoverridevirtual | 
String representation of the Class Type.
Implements NAV::Node.
Definition at line 58 of file ImuSimulator.cpp.
      
  | 
  staticnodiscard | 
String representation of the Class Type.
Definition at line 53 of file ImuSimulator.cpp.
      
  | 
  private | 
Apply the Earth rotation rate to the measured angular rates.
Definition at line 243 of file ImuSimulator.hpp.
      
  | 
  private | 
Apply the transport rate to the measured angular rates.
Definition at line 246 of file ImuSimulator.hpp.
      
  | 
  private | 
Apply the centrifugal acceleration to the measured accelerations.
Definition at line 240 of file ImuSimulator.hpp.
      
  | 
  private | 
Harmonic Oscillation Amplitude Factor of the circle radius [-].
Definition at line 164 of file ImuSimulator.hpp.
      
  | 
  private | 
Harmonic Oscillation Frequency on the circular trajectory [cycles/revolution].
Definition at line 161 of file ImuSimulator.hpp.
      
  | 
  private | 
Amount of circles to simulate before stopping.
Definition at line 227 of file ImuSimulator.hpp.
      
  | 
  private | 
Apply the coriolis acceleration to the measured accelerations.
Definition at line 237 of file ImuSimulator.hpp.
      
  | 
  private | 
Duration from the CSV file in [s].
Definition at line 221 of file ImuSimulator.hpp.
      
  | 
  private | 
Orientation of the vehicle [roll, pitch, yaw] [rad].
Definition at line 155 of file ImuSimulator.hpp.
      
  | 
  private | 
Frequency to sample the position with in [Hz].
Definition at line 126 of file ImuSimulator.hpp.
      
  | 
  private | 
Last time the GNSS message was calculated in [s].
Definition at line 297 of file ImuSimulator.hpp.
      
  | 
  private | 
Counter to calculate the GNSS update time.
Definition at line 289 of file ImuSimulator.hpp.
      
  | 
  private | 
Gravitation model selected in the GUI.
Definition at line 234 of file ImuSimulator.hpp.
      
  | 
  private | 
Frequency to sample the IMU with in [Hz].
Definition at line 124 of file ImuSimulator.hpp.
      
  | 
  private | 
Frequency to calculate the delta IMU values in [Hz].
Definition at line 122 of file ImuSimulator.hpp.
      
  | 
  private | 
Counter to calculate the internal IMU update time.
Definition at line 285 of file ImuSimulator.hpp.
      
  | 
  private | 
Last time the IMU message was calculated in [s].
Definition at line 295 of file ImuSimulator.hpp.
      
  | 
  private | 
Counter to calculate the IMU update time.
Definition at line 287 of file ImuSimulator.hpp.
      
  | 
  private | 
Distance in [m] to the start position to stop the simulation.
Definition at line 224 of file ImuSimulator.hpp.
      
  | 
  private | 
Last calculated position for the GNSS in linear mode for iterative calculations as latitude, longitude, altitude [rad, rad, m].
Definition at line 301 of file ImuSimulator.hpp.
      
  | 
  private | 
Last calculated position for the IMU in linear mode for iterative calculations as latitude, longitude, altitude [rad, rad, m].
Definition at line 299 of file ImuSimulator.hpp.
      
  | 
  private | 
Start Velocity of the vehicle in local-navigation frame cooridnates in [m/s].
Definition at line 158 of file ImuSimulator.hpp.
      
  | 
  private | 
Last calculated acceleration measurement in platform coordinates [m/s²].
Definition at line 303 of file ImuSimulator.hpp.
      
  | 
  private | 
Last calculated angular rate measurement in platform coordinates [rad/s].
Definition at line 305 of file ImuSimulator.hpp.
      
  | 
  private | 
In the GUI selected denominator of petals (2*k for even k, k for uneven k) of the rose figure.
Definition at line 197 of file ImuSimulator.hpp.
      
  | 
  private | 
In the GUI selected numerator of petals (2*k for even k, k for uneven k) of the rose figure.
Definition at line 194 of file ImuSimulator.hpp.
      
  | 
  private | 
Simulation duration needed for the rose figure.
Definition at line 203 of file ImuSimulator.hpp.
      
  | 
  private | 
Maxmimum step length for the spline points for the rose figure [m]. Points will be spaced between [L/3 L].
Definition at line 200 of file ImuSimulator.hpp.
      
  | 
  private | 
Amount of rose figures to simulate before stopping.
Definition at line 230 of file ImuSimulator.hpp.
      
  | 
  private | 
Duration to simulate in [s].
Definition at line 218 of file ImuSimulator.hpp.
      
  | 
  private | 
Condition which has to be met to stop the simulation.
Definition at line 215 of file ImuSimulator.hpp.
| struct { ... } NAV::ImuSimulator::_splines | 
Assign a variable that holds the Spline information.
      
  | 
  private | 
Start position in local navigation coordinates (latitude, longitude, altitude) [rad, rad, m]
Definition at line 152 of file ImuSimulator.hpp.
      
  | 
  private | 
Global starttime.
Definition at line 117 of file ImuSimulator.hpp.
      
  | 
  private | 
Time Format to input the start time with.
Definition at line 114 of file ImuSimulator.hpp.
      
  | 
  private | 
Source for the start time, selected in the GUI.
Definition at line 111 of file ImuSimulator.hpp.
      
  | 
  private | 
In the GUI selected direction of the circular trajectory (used by circular and rose figure)
Definition at line 179 of file ImuSimulator.hpp.
      
  | 
  private | 
Horizontal speed of the vehicle in the tangential plane in [m/s] (used by circular and rose figure)
Definition at line 185 of file ImuSimulator.hpp.
      
  | 
  private | 
In the GUI selected radius of the circular trajectory (used by circular and rose figure)
Definition at line 191 of file ImuSimulator.hpp.
      
  | 
  private | 
In the GUI selected origin angle of the circular trajectory in [rad].
Definition at line 182 of file ImuSimulator.hpp.
      
  | 
  private | 
Selected trajectory type in the GUI.
Definition at line 146 of file ImuSimulator.hpp.
      
  | 
  private | 
Vertical speed of the vehicle in the tangential plane in [m/s] (used by circular and rose figure)
Definition at line 188 of file ImuSimulator.hpp.
      
  | 
  staticconstexprprivate | 
Object (CsvData)
Definition at line 73 of file ImuSimulator.hpp.
      
  | 
  staticconstexprprivate | 
Update rate for the internal solution of linear movement in [Hz].
Definition at line 292 of file ImuSimulator.hpp.
      
  | 
  staticconstexprprivate | 
Flow (ImuObs)
Definition at line 74 of file ImuSimulator.hpp.
      
  | 
  staticconstexprprivate | 
Flow (PosVelAtt)
Definition at line 75 of file ImuSimulator.hpp.
| CubicSpline<long double> NAV::ImuSimulator::pitch | 
Pitch angle [rad].
Definition at line 276 of file ImuSimulator.hpp.
| CubicSpline<long double> NAV::ImuSimulator::roll | 
Roll angle [rad].
Definition at line 275 of file ImuSimulator.hpp.
| double NAV::ImuSimulator::sampleInterval | 
Spline sample interval.
Definition at line 271 of file ImuSimulator.hpp.
| CubicSpline<long double> NAV::ImuSimulator::x | 
ECEF X Position [m].
Definition at line 272 of file ImuSimulator.hpp.
| CubicSpline<long double> NAV::ImuSimulator::y | 
ECEF Y Position [m].
Definition at line 273 of file ImuSimulator.hpp.
| CubicSpline<long double> NAV::ImuSimulator::yaw | 
Yaw angle [rad].
Definition at line 277 of file ImuSimulator.hpp.
| CubicSpline<long double> NAV::ImuSimulator::z | 
ECEF Z Position [m].
Definition at line 274 of file ImuSimulator.hpp.