The class is an implementation of the dynamical system defined by an inertial measurement unit (IMU) fixed on a rigid body. The state is the position velocity and acceleration and the orientaion and rotation velocity and acceleration. The sensors are the accelerometer and the gyrometer. More...
#include <state-observation/dynamical-system/imu-dynamical-system.hpp>


Classes | |
| struct | indexes |
Public Member Functions | |
| IMUDynamicalSystem (bool withGyroBias=false) | |
| The constructor. More... | |
| virtual | ~IMUDynamicalSystem () |
| The virtual destructor. More... | |
| virtual Vector | stateDynamics (const Vector &x, const Vector &u, TimeIndex k) |
| Description of the state dynamics. More... | |
| virtual Vector | measureDynamics (const Vector &x, const Vector &u, TimeIndex k) |
| Description of the sensor's dynamics. More... | |
| virtual void | setProcessNoise (NoiseBase *) |
| Sets a noise which disturbs the state dynamics. More... | |
| virtual void | resetProcessNoise () |
| Removes the process noise. More... | |
| virtual NoiseBase * | getProcessNoise () const |
| Gets the process noise. More... | |
| virtual void | setMeasurementNoise (NoiseBase *) |
| Sets a noise which disturbs the measurements. More... | |
| virtual void | resetMeasurementNoise () |
| Removes the measurement noise. More... | |
| virtual NoiseBase * | getMeasurementNoise () const |
| Gets a pointer on the measurement noise. More... | |
| virtual void | setSamplingPeriod (double dt) |
| Set the period of the time discretization. More... | |
| virtual Index | getStateSize () const |
| Gets the state size. More... | |
| virtual Index | getInputSize () const |
| Gets the input size. More... | |
| virtual Index | getMeasurementSize () const |
| Gets the measurement size. More... | |
| void | setWithGyroBias (bool) |
| Set whether we use Gyro Bias. More... | |
| void | updatestatesize () |
Public Member Functions inherited from stateObservation::DynamicalSystemFunctorBase | |
| DynamicalSystemFunctorBase () | |
| virtual | ~DynamicalSystemFunctorBase () |
| virtual void | reset () |
| virtual bool | checkStateVector (const Vector &) |
| Gives a boolean answer on whether or not the vector is correctly sized to be a state vector. More... | |
| virtual bool | checkInputvector (const Vector &) |
| Gives a boolean answer on whether or not the vector is correctly sized to be an input vector. More... | |
Protected Member Functions | |
| Quaternion | computeQuaternion_ (const Vector3 &x) |
Protected Member Functions inherited from stateObservation::DynamicalSystemFunctorBase | |
| void | assertStateVector_ (const Vector &v) |
| void | assertInputVector_ (const Vector &v) |
Protected Attributes | |
| AccelerometerGyrometer | sensor_ |
| NoiseBase * | processNoise_ |
| double | dt_ |
| Vector3Unaligned | orientationVector_ |
| QuaternionUnaligned | quaternion_ |
| Index | statesize_ |
| the state size may be bigger if the bias is considered More... | |
| bool | withGyroBias_ |
Static Protected Attributes | |
| static const Index | stateSizeBase_ = 18 |
| static const Index | inputSize_ = 6 |
| static const Index | measurementSize_ = 6 |
| static constexpr double | one_ = 0.9999 |
| the factor that approximate the "one" to avoid drifting of unobservable values More... | |
The class is an implementation of the dynamical system defined by an inertial measurement unit (IMU) fixed on a rigid body. The state is the position velocity and acceleration and the orientaion and rotation velocity and acceleration. The sensors are the accelerometer and the gyrometer.
| stateObservation::IMUDynamicalSystem::IMUDynamicalSystem | ( | bool | withGyroBias = false | ) |
The constructor.
|
virtual |
The virtual destructor.
|
protected |
|
virtual |
Gets the input size.
Implements stateObservation::DynamicalSystemFunctorBase.
|
virtual |
Gets a pointer on the measurement noise.
|
virtual |
Gets the measurement size.
Implements stateObservation::DynamicalSystemFunctorBase.
|
virtual |
Gets the process noise.
|
virtual |
Gets the state size.
Implements stateObservation::DynamicalSystemFunctorBase.
|
virtual |
Description of the sensor's dynamics.
Implements stateObservation::DynamicalSystemFunctorBase.
|
virtual |
Removes the measurement noise.
|
virtual |
Removes the process noise.
|
virtual |
Sets a noise which disturbs the measurements.
|
virtual |
Sets a noise which disturbs the state dynamics.
|
virtual |
Set the period of the time discretization.
| void stateObservation::IMUDynamicalSystem::setWithGyroBias | ( | bool | ) |
Set whether we use Gyro Bias.
|
virtual |
Description of the state dynamics.
Implements stateObservation::DynamicalSystemFunctorBase.
|
inline |
|
protected |
|
staticprotected |
|
staticprotected |
|
staticconstexprprotected |
the factor that approximate the "one" to avoid drifting of unobservable values
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
the state size may be bigger if the bias is considered
|
staticprotected |
|
protected |