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:
Call initialize() or set the required parameters directly in params_.
Integrate measurements with integrate_measurement()
Repeat (2) N times as needed.
Take the estimation up to this point with current_integration_state() and reset with reset_integration() if you create a new key-frame.
Go to (2).
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: