class mola::RotationIntegrator

Overview

Integrates gyroscope angular velocity readings.

Bias is assumed to be constant, although the user is free of updating it at any moment by accessing params_.

See IMUIntegrationParams for a list of related papers explaining the methods and parameters.

Usage:

Initially based in part on GTSAM sources gtsam::PreintegratedRotation.

See also:

IMUIntegrator

#include <RotationIntegrator.h>

class RotationIntegrator
{
public:
    // structs

    struct IntegrationState;

    // fields

    RotationIntegrationParams params_;

    // methods

    void initialize(const mrpt::containers::yaml& cfg);
    void reset_integration();
    const IntegrationState& current_integration_state() const;
    void integrate_measurement(const mrpt::math::TVector3D& w, double dt);
};

Methods

void initialize(const mrpt::containers::yaml& cfg)

Initializes the object and reads all parameters from a YAML node.

Parameters:

cfg

a YAML node with a dictionary of parameters to load from, as expected by RotationIntegrationParams (see its docs).

void reset_integration()

Resets the integrator state to an initial state.

See also:

currentIntegrationState

void integrate_measurement(const mrpt::math::TVector3D& w, double dt)

Accumulates a new gyroscope measurement of the angular velocity (ω) into the current preintegration state, integrating it forward in time for a period dt [s].

See also:

current_integration_state(), reset_integration()