Inertial Measurement Integrator.
More...
Inertial Measurement Integrator.
Definition at line 31 of file InertialPreIntegrator.hpp.
◆ Measurement
◆ IntegrationFrame
Available Integration Frames.
Enumerator |
---|
ECEF | Earth-Centered Earth-Fixed frame.
|
NED | Local North-East-Down frame.
|
Definition at line 35 of file InertialPreIntegrator.hpp.
◆ InertialPreIntegrator() [1/2]
NAV::InertialPreIntegrator::InertialPreIntegrator |
( |
| ) |
|
|
default |
◆ InertialPreIntegrator() [2/2]
NAV::InertialPreIntegrator::InertialPreIntegrator |
( |
IntegrationFrame | integrationFrame | ) |
|
|
explicit |
◆ 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] | meas | Inertial measurement |
[in] | imuPos | IMU mounting position connecting the platform to the body frame |
[in] | nameId | Name 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] | pvaOld | Position, velocity and attitude at the start of the preintegration interval |
[in] | imuNew | The IMU state at the moment of evaluation |
[in] | imuPos | IMU mounting position connecting the platform to the body frame |
[in] | nameId | Name 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()
Get the Covariance Matrix of the preintegrated measurements (3x attitude, 3x velocity, 3x position)
Definition at line 123 of file InertialPreIntegrator.cpp.
◆ getIntegrationFrame()
◆ reset()
void NAV::InertialPreIntegrator::reset |
( |
| ) |
|
◆ setImuNoiseScaleMatrix()
void NAV::InertialPreIntegrator::setImuNoiseScaleMatrix |
( |
const Eigen::Matrix6d & | W | ) |
|
◆ from_json
Read info from a json object.
- Parameters
-
[in] | j | Json variable to read info from |
[out] | data | Output 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] | label | Label to show. This has to be a unique id for ImGui. |
[in] | integrator | Reference to the integrator to configure |
[in] | width | Width of the widget |
Definition at line 133 of file InertialPreIntegrator.cpp.
◆ to_json
Write info to a json object.
- Parameters
-
[out] | j | Json output |
[in] | data | Object to read info from |
Definition at line 197 of file InertialPreIntegrator.cpp.
◆ to_string
Converts the enum to a string.
- Parameters
-
[in] | frame | Enum value to convert into text |
- Returns
- String representation of the enum
Definition at line 213 of file InertialPreIntegrator.cpp.
◆ _attitudeIncrement
Eigen::Quaterniond NAV::InertialPreIntegrator::_attitudeIncrement |
|
private |
◆ _covMatrix
◆ _gravitationModel
◆ _imuNoiseScale_W
std::optional<Eigen::Matrix6d> NAV::InertialPreIntegrator::_imuNoiseScale_W |
|
private |
◆ _imuState
ImuState<double> NAV::InertialPreIntegrator::_imuState |
|
private |
◆ _integrationFrame
◆ _lockIntegrationFrame
bool NAV::InertialPreIntegrator::_lockIntegrationFrame |
|
private |
◆ _pAtt_pOmega
Eigen::Matrix3d NAV::InertialPreIntegrator::_pAtt_pOmega |
|
private |
◆ _positionIncrement
Eigen::Vector3d NAV::InertialPreIntegrator::_positionIncrement |
|
private |
◆ _pPos_pAccel
Eigen::Matrix3d NAV::InertialPreIntegrator::_pPos_pAccel |
|
private |
◆ _pPos_pOmega
Eigen::Matrix3d NAV::InertialPreIntegrator::_pPos_pOmega |
|
private |
◆ _pVel_pAccel
Eigen::Matrix3d NAV::InertialPreIntegrator::_pVel_pAccel |
|
private |
◆ _pVel_pOmega
Eigen::Matrix3d NAV::InertialPreIntegrator::_pVel_pOmega |
|
private |
◆ _timeIncrement
double NAV::InertialPreIntegrator::_timeIncrement |
|
private |
◆ _velocityIncrement
Eigen::Vector3d NAV::InertialPreIntegrator::_velocityIncrement |
|
private |
The documentation for this class was generated from the following files: