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

Inertial Measurement Integrator. More...

Data Structures

struct  GenericMeasurement
 Inertial Measurement for a generic type. More...
struct  ImuMeasurement
 IMU measurement. More...
struct  ImuState
 IMU state. More...
struct  PVAState
 Position, velocity and attitude state. More...

Public Types

enum class  IntegrationFrame : uint8_t {
  ECEF ,
  NED
}
 Available Integration Frames. More...
using Measurement
 Inertial measurements.

Public Member Functions

void addInertialMeasurement (const Measurement &meas, const ImuPos &imuPos, const std::string &nameId)
 Adds a inertial measurement to the relative motion increments.
template<typename T>
PVAState< T > calcIntegratedState (const PVAState< T > &pvaOld, const ImuState< T > &imuNew, const ImuPos &imuPos, const std::string &nameId)
 Calculates the state using the preintegrated relative motion increments.
const Eigen::Matrix9dgetCovMatrix () const
 Get the Covariance Matrix of the preintegrated measurements (3x attitude, 3x velocity, 3x position)
IntegrationFrame getIntegrationFrame () const
 Returns the selected integration frame.
 InertialPreIntegrator ()=default
 Default Constructor.
 InertialPreIntegrator (IntegrationFrame integrationFrame)
 Constructor.
void reset ()
 Clears all internal data.
void setImuNoiseScaleMatrix (const Eigen::Matrix6d &W)
 Set the IMU Noise Scale Matrix.

Private Attributes

Eigen::Quaterniond _attitudeIncrement
 Relative motion increment for the attitude bi_q_bj.
Eigen::Matrix9d _covMatrix
 Incremental covariance matrix (3x attitude, 3x velocity, 3x position)
GravitationModel _gravitationModel
 Gravity Model to use.
std::optional< Eigen::Matrix6d_imuNoiseScale_W
 Noise scale matrix of the IMU.
ImuState< double > _imuState
 IMU state used to calculate the increments.
IntegrationFrame _integrationFrame
 Frame to integrate the observations in.
bool _lockIntegrationFrame
 Wether to lock the integration frame.
Eigen::Matrix3d _pAtt_pOmega
 Partial derivative of the attitude increment after the angular rate bias.
Eigen::Vector3d _positionIncrement
 Relative motion increment for the position.
Eigen::Matrix3d _pPos_pAccel
 Partial derivative of the position increment after the acceleration bias.
Eigen::Matrix3d _pPos_pOmega
 Partial derivative of the position increment after the angular rate bias.
Eigen::Matrix3d _pVel_pAccel
 Partial derivative of the velocity increment after the acceleration bias.
Eigen::Matrix3d _pVel_pOmega
 Partial derivative of the velocity increment after the angular rate bias.
double _timeIncrement
 Time accumulated for each increment.
Eigen::Vector3d _velocityIncrement
 Relative motion increment for the velocity.

Friends

void from_json (const json &j, InertialPreIntegrator &data)
 Read info from a json object.
bool InertialPreIntegratorGui (const char *label, InertialPreIntegrator &integrator, float width=250.0F)
 Shows a GUI for advanced configuration of the InertialPreIntegrator.
void to_json (json &j, const InertialPreIntegrator &data)
 Write info to a json object.
const char * to_string (InertialPreIntegrator::IntegrationFrame frame)
 Converts the enum to a string.

Detailed Description

Inertial Measurement Integrator.

Definition at line 31 of file InertialPreIntegrator.hpp.

Member Typedef Documentation

◆ Measurement

Inertial measurements.

Definition at line 91 of file InertialPreIntegrator.hpp.

Member Enumeration Documentation

◆ IntegrationFrame

enum class NAV::InertialPreIntegrator::IntegrationFrame : uint8_t
strong

Available Integration Frames.

Enumerator
ECEF 

Earth-Centered Earth-Fixed frame.

NED 

Local North-East-Down frame.

Definition at line 35 of file InertialPreIntegrator.hpp.

Constructor & Destructor Documentation

◆ InertialPreIntegrator() [1/2]

NAV::InertialPreIntegrator::InertialPreIntegrator ( )
default

Default Constructor.

◆ InertialPreIntegrator() [2/2]

NAV::InertialPreIntegrator::InertialPreIntegrator ( IntegrationFrame integrationFrame)
explicit

Constructor.

Parameters
integrationFrameIntegration frame to lock to

Definition at line 26 of file InertialPreIntegrator.cpp.

Member Function Documentation

◆ addInertialMeasurement()

void NAV::InertialPreIntegrator::addInertialMeasurement ( const Measurement & meas,
const ImuPos & imuPos,
const std::string & nameId )

Adds a inertial measurement to the relative motion increments.

Parameters
[in]measInertial measurement
[in]imuPosIMU mounting position connecting the platform to the body frame
[in]nameIdName and id of the calling node for logging

Definition at line 49 of file InertialPreIntegrator.cpp.

◆ calcIntegratedState()

template<typename T>
PVAState< T > NAV::InertialPreIntegrator::calcIntegratedState ( const PVAState< T > & pvaOld,
const ImuState< T > & imuNew,
const ImuPos & imuPos,
const std::string & nameId )
inline

Calculates the state using the preintegrated relative motion increments.

Parameters
[in]pvaOldPosition, velocity and attitude at the start of the preintegration interval
[in]imuNewThe IMU state at the moment of evaluation
[in]imuPosIMU mounting position connecting the platform to the body frame
[in]nameIdName and id of the calling node for logging
Returns
The position, velocity and attitude at the end of the preintegration interval

Definition at line 120 of file InertialPreIntegrator.hpp.

◆ getCovMatrix()

const Eigen::Matrix9d & NAV::InertialPreIntegrator::getCovMatrix ( ) const
nodiscard

Get the Covariance Matrix of the preintegrated measurements (3x attitude, 3x velocity, 3x position)

Definition at line 123 of file InertialPreIntegrator.cpp.

◆ getIntegrationFrame()

InertialPreIntegrator::IntegrationFrame NAV::InertialPreIntegrator::getIntegrationFrame ( ) const
nodiscard

Returns the selected integration frame.

Definition at line 128 of file InertialPreIntegrator.cpp.

◆ reset()

void NAV::InertialPreIntegrator::reset ( )

Clears all internal data.

Definition at line 29 of file InertialPreIntegrator.cpp.

◆ setImuNoiseScaleMatrix()

void NAV::InertialPreIntegrator::setImuNoiseScaleMatrix ( const Eigen::Matrix6d & W)

Set the IMU Noise Scale Matrix.

Parameters
[in]WIMU Noise Scale Matrix

Definition at line 44 of file InertialPreIntegrator.cpp.

◆ from_json

void from_json ( const json & j,
InertialPreIntegrator & data )
friend

Read info from a json object.

Parameters
[in]jJson variable to read info from
[out]dataOutput object

Definition at line 206 of file InertialPreIntegrator.cpp.

◆ InertialPreIntegratorGui

bool InertialPreIntegratorGui ( const char * label,
InertialPreIntegrator & integrator,
float width = 250.0F )
friend

Shows a GUI for advanced configuration of the InertialPreIntegrator.

Parameters
[in]labelLabel to show. This has to be a unique id for ImGui.
[in]integratorReference to the integrator to configure
[in]widthWidth of the widget

Definition at line 133 of file InertialPreIntegrator.cpp.

◆ to_json

void to_json ( json & j,
const InertialPreIntegrator & data )
friend

Write info to a json object.

Parameters
[out]jJson output
[in]dataObject to read info from

Definition at line 197 of file InertialPreIntegrator.cpp.

◆ to_string

const char * to_string ( InertialPreIntegrator::IntegrationFrame frame)
friend

Converts the enum to a string.

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

Definition at line 213 of file InertialPreIntegrator.cpp.

Field Documentation

◆ _attitudeIncrement

Eigen::Quaterniond NAV::InertialPreIntegrator::_attitudeIncrement
private

Relative motion increment for the attitude bi_q_bj.

Definition at line 178 of file InertialPreIntegrator.hpp.

◆ _covMatrix

Eigen::Matrix9d NAV::InertialPreIntegrator::_covMatrix
private

Incremental covariance matrix (3x attitude, 3x velocity, 3x position)

Definition at line 182 of file InertialPreIntegrator.hpp.

◆ _gravitationModel

GravitationModel NAV::InertialPreIntegrator::_gravitationModel
private

Gravity Model to use.

Definition at line 170 of file InertialPreIntegrator.hpp.

◆ _imuNoiseScale_W

std::optional<Eigen::Matrix6d> NAV::InertialPreIntegrator::_imuNoiseScale_W
private

Noise scale matrix of the IMU.

Definition at line 192 of file InertialPreIntegrator.hpp.

◆ _imuState

ImuState<double> NAV::InertialPreIntegrator::_imuState
private

IMU state used to calculate the increments.

Definition at line 190 of file InertialPreIntegrator.hpp.

◆ _integrationFrame

IntegrationFrame NAV::InertialPreIntegrator::_integrationFrame
private

Frame to integrate the observations in.

Definition at line 167 of file InertialPreIntegrator.hpp.

◆ _lockIntegrationFrame

bool NAV::InertialPreIntegrator::_lockIntegrationFrame
private

Wether to lock the integration frame.

Definition at line 173 of file InertialPreIntegrator.hpp.

◆ _pAtt_pOmega

Eigen::Matrix3d NAV::InertialPreIntegrator::_pAtt_pOmega
private

Partial derivative of the attitude increment after the angular rate bias.

Definition at line 184 of file InertialPreIntegrator.hpp.

◆ _positionIncrement

Eigen::Vector3d NAV::InertialPreIntegrator::_positionIncrement
private

Relative motion increment for the position.

Definition at line 180 of file InertialPreIntegrator.hpp.

◆ _pPos_pAccel

Eigen::Matrix3d NAV::InertialPreIntegrator::_pPos_pAccel
private

Partial derivative of the position increment after the acceleration bias.

Definition at line 187 of file InertialPreIntegrator.hpp.

◆ _pPos_pOmega

Eigen::Matrix3d NAV::InertialPreIntegrator::_pPos_pOmega
private

Partial derivative of the position increment after the angular rate bias.

Definition at line 188 of file InertialPreIntegrator.hpp.

◆ _pVel_pAccel

Eigen::Matrix3d NAV::InertialPreIntegrator::_pVel_pAccel
private

Partial derivative of the velocity increment after the acceleration bias.

Definition at line 185 of file InertialPreIntegrator.hpp.

◆ _pVel_pOmega

Eigen::Matrix3d NAV::InertialPreIntegrator::_pVel_pOmega
private

Partial derivative of the velocity increment after the angular rate bias.

Definition at line 186 of file InertialPreIntegrator.hpp.

◆ _timeIncrement

double NAV::InertialPreIntegrator::_timeIncrement
private

Time accumulated for each increment.

Definition at line 177 of file InertialPreIntegrator.hpp.

◆ _velocityIncrement

Eigen::Vector3d NAV::InertialPreIntegrator::_velocityIncrement
private

Relative motion increment for the velocity.

Definition at line 179 of file InertialPreIntegrator.hpp.


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