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

Inertial Measurement Integrator. More...

Classes

struct  Measurement
 Inertial Measurement. More...
 

Public Types

enum class  IntegrationAlgorithm : uint8_t {
  SingleStepRungeKutta1 ,
  SingleStepRungeKutta2 ,
  SingleStepHeun2 ,
  SingleStepRungeKutta3 ,
  SingleStepHeun3 ,
  SingleStepRungeKutta4 ,
  MultiStepRK3 ,
  MultiStepRK4 ,
  COUNT
}
 Available Integration Algorithms. More...
 
enum class  IntegrationFrame : uint8_t {
  ECEF ,
  NED
}
 Available Integration Frames. More...
 

Public Member Functions

void applySensorBiasesIncrements (const Eigen::Vector3d &p_deltaBiasAcceleration, const Eigen::Vector3d &p_deltaBiasAngularRate)
 Sets the sensor biases increment.
 
void applyStateErrors_e (const Eigen::Vector3d &e_positionError, const Eigen::Vector3d &e_velocityError, const Eigen::Vector3d &e_attitudeError_b)
 Apply the errors to the latest state.
 
void applyStateErrors_n (const Eigen::Vector3d &lla_positionError, const Eigen::Vector3d &n_velocityError, const Eigen::Vector3d &n_attitudeError_b)
 Apply the errors to the latest state.
 
std::shared_ptr< PosVelAttcalcInertialSolution (const InsTime &obsTime, const Eigen::Vector3d &p_acceleration, const Eigen::Vector3d &p_angularRate, const ImuPos &imuPos)
 Calculates the inertial navigation solution.
 
std::shared_ptr< PosVelAttcalcInertialSolutionDelta (const InsTime &obsTime, const double &dt, const Eigen::Vector3d &p_deltaVelocity, const Eigen::Vector3d &p_deltaTheta, const ImuPos &imuPos)
 Calculates the inertial navigation solution.
 
IntegrationFrame getIntegrationFrame () const
 Returns the selected integration frame.
 
std::optional< std::reference_wrapper< const PosVelAtt > > getLatestState () const
 Get the latest state if it exists.
 
const ScrollingBuffer< Measurement > & getMeasurements () const
 Get the measurements buffer.
 
bool hasInitialPosition () const
 Checks if an initial position is set.
 
std::optional< Eigen::Vector3d > p_calcCurrentAcceleration () const
 Calculate the current acceleration, if measurements area available.
 
std::optional< Eigen::Vector3d > p_calcCurrentAngularRate () const
 Calculate the current angular rate, if measurements area available.
 
const Eigen::Vector3d & p_getLastAccelerationBias () const
 Return the last acceleration bias in platform frame coordinates in [m/s^2].
 
const Eigen::Vector3d & p_getLastAngularRateBias () const
 Return the last angular rate bias in platform frame coordinates in [rad/s].
 
void reset ()
 Clears all internal data.
 
void setInitialState (const PosVelAtt &state)
 Sets the initial state.
 
void setState (const PosVelAtt &state)
 Pushes the state to the list of states.
 
void setTotalSensorBiases (const Eigen::Vector3d &p_biasAcceleration, const Eigen::Vector3d &p_biasAngularRate)
 Sets the sensor biases total values.
 

Private Member Functions

std::shared_ptr< PosVelAttcalcInertialSolutionFromMeasurementBuffer (const ImuPos &imuPos)
 Calculates the inertial navigation solution.
 
void setBufferSizes ()
 Resizes the measurement and state buffers depending on the integration algorithm.
 

Private Attributes

IntegrationAlgorithm _integrationAlgorithm
 Integration algorithm used for the update.
 
IntegrationFrame _integrationFrame
 Frame to integrate the observations in.
 
ScrollingBuffer< Measurement_measurements
 List of measurements. Length depends on algorithm used.
 
PosVelAttDerivativeConstants< double > _posVelAttDerivativeConstants
 Settings for the models to use.
 
ScrollingBuffer< PosVelAtt_states
 List of states. Length depends on algorithm used.
 
Eigen::Vector3d p_lastBiasAcceleration
 Acceleration bias in platform frame coordinates in [m/s^2].
 
Eigen::Vector3d p_lastBiasAngularRate
 Angular rate bias in platform frame coordinates in [rad/s].
 

Friends

void from_json (const json &j, InertialIntegrator &data)
 Read info from a json object.
 
bool InertialIntegratorGui (const char *label, InertialIntegrator &integrator, float width=250.0F)
 Shows a GUI for advanced configuration of the InertialIntegrator.
 
void to_json (json &j, const InertialIntegrator &data)
 Write info to a json object.
 

Detailed Description

Inertial Measurement Integrator.

Member Enumeration Documentation

◆ IntegrationAlgorithm

enum class NAV::InertialIntegrator::IntegrationAlgorithm : uint8_t
strong

Available Integration Algorithms.

Enumerator
SingleStepRungeKutta1 

Runge-Kutta 1st order (explicit) / (Forward) Euler method.

SingleStepRungeKutta2 

Runge-Kutta 2nd order (explicit) / Explicit midpoint method.

SingleStepHeun2 

Heun's method (2nd order) (explicit)

SingleStepRungeKutta3 

Runge-Kutta 3rd order (explicit) / Simpson's rule.

SingleStepHeun3 

Heun's method (3nd order) (explicit)

SingleStepRungeKutta4 

Runge-Kutta 4th order (explicit)

MultiStepRK3 

Multistep Runge-Kutta 3rd order (explicit) / Simpson's rule (taking 2 old epochs into account)

MultiStepRK4 

Multistep Runge-Kutta 4th order (explicit) (taking 2 old epochs into account)

COUNT 

Amount of available integration algorithms.

◆ IntegrationFrame

enum class NAV::InertialIntegrator::IntegrationFrame : uint8_t
strong

Available Integration Frames.

Enumerator
ECEF 

Earth-Centered Earth-Fixed frame.

NED 

Local North-East-Down frame.

Member Function Documentation

◆ applySensorBiasesIncrements()

void NAV::InertialIntegrator::applySensorBiasesIncrements ( const Eigen::Vector3d & p_deltaBiasAcceleration,
const Eigen::Vector3d & p_deltaBiasAngularRate )

Sets the sensor biases increment.

Parameters
[in]p_deltaBiasAccelerationAcceleration bias increment in platform frame coordinates in [m/s^2]
[in]p_deltaBiasAngularRateAngular rate bias increment in platform frame coordinates in [rad/s]

◆ applyStateErrors_e()

void NAV::InertialIntegrator::applyStateErrors_e ( const Eigen::Vector3d & e_positionError,
const Eigen::Vector3d & e_velocityError,
const Eigen::Vector3d & e_attitudeError_b )

Apply the errors to the latest state.

Parameters
[in]e_positionErrorδr_e The position error in e frame coordinates in [m]
[in]e_velocityErrorδ𝐯_e The velocity error in e frame coordinates in [m/s]
[in]e_attitudeError_bδ𝛙_eb_e The attitude error in e frame coordinates in [rad]

◆ applyStateErrors_n()

void NAV::InertialIntegrator::applyStateErrors_n ( const Eigen::Vector3d & lla_positionError,
const Eigen::Vector3d & n_velocityError,
const Eigen::Vector3d & n_attitudeError_b )

Apply the errors to the latest state.

Parameters
[in]lla_positionErrorδ𝐩_n = [δ𝜙 δλ δ𝘩] The position error (latitude, longitude, altitude) in [rad, rad, m]
[in]n_velocityErrorδ𝐯_n The velocity error in n frame coordinates in [m/s]
[in]n_attitudeError_bδ𝛙_nb_n The attitude error in n frame coordinates in [rad]

◆ calcInertialSolution()

std::shared_ptr< PosVelAtt > NAV::InertialIntegrator::calcInertialSolution ( const InsTime & obsTime,
const Eigen::Vector3d & p_acceleration,
const Eigen::Vector3d & p_angularRate,
const ImuPos & imuPos )

Calculates the inertial navigation solution.

Parameters
[in]obsTimeTime of the observation
[in]p_accelerationAcceleration in platform frame coordinates in [m/s^2]
[in]p_angularRateAngular rate in platform frame coordinates in [rad/s]
[in]imuPosIMU platform frame position with respect to body frame
Returns
The new state at the observation time

◆ calcInertialSolutionDelta()

std::shared_ptr< PosVelAtt > NAV::InertialIntegrator::calcInertialSolutionDelta ( const InsTime & obsTime,
const double & dt,
const Eigen::Vector3d & p_deltaVelocity,
const Eigen::Vector3d & p_deltaTheta,
const ImuPos & imuPos )

Calculates the inertial navigation solution.

Parameters
[in]obsTimeTime of the observation
[in]dtDelta time over which the deltaVelocity and deltaTheta were measured in [s]
[in]p_deltaVelocityIntegrated acceleration in platform frame coordinates in [m/s]
[in]p_deltaThetaIntegrated angular rate in platform frame coordinates in [rad]
[in]imuPosIMU platform frame position with respect to body frame
Returns
The new state at the observation time

◆ calcInertialSolutionFromMeasurementBuffer()

std::shared_ptr< PosVelAtt > NAV::InertialIntegrator::calcInertialSolutionFromMeasurementBuffer ( const ImuPos & imuPos)
private

Calculates the inertial navigation solution.

Parameters
[in]imuPosIMU platform frame position with respect to body frame
Returns
The new state at the observation time

◆ setInitialState()

void NAV::InertialIntegrator::setInitialState ( const PosVelAtt & state)

Sets the initial state.

Parameters
[in]stateState to set

◆ setState()

void NAV::InertialIntegrator::setState ( const PosVelAtt & state)

Pushes the state to the list of states.

Parameters
[in]stateState to set

◆ setTotalSensorBiases()

void NAV::InertialIntegrator::setTotalSensorBiases ( const Eigen::Vector3d & p_biasAcceleration,
const Eigen::Vector3d & p_biasAngularRate )

Sets the sensor biases total values.

Parameters
[in]p_biasAccelerationAcceleration bias in platform frame coordinates in [m/s^2]
[in]p_biasAngularRateAngular rate bias in platform frame coordinates in [rad/s]

Friends And Related Symbol Documentation

◆ from_json

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

Read info from a json object.

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

◆ InertialIntegratorGui

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

Shows a GUI for advanced configuration of the InertialIntegrator.

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

◆ to_json

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

Write info to a json object.

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

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