13#ifndef IMU_DYNAMICAL_SYSTEM_HPP
14#define IMU_DYNAMICAL_SYSTEM_HPP
16#include <state-observation/api.h>
80 statesize_ = stateSizeBase_ + 3;
84 statesize_ = stateSizeBase_;
90 static const Index gyroBias = 18;
105 static const Index stateSizeBase_ = 18;
108 static const Index measurementSize_ = 6;
113 static constexpr double one_ = 0.9999;
117 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Implements the accelerometer-gyrometer inertial measuremen.
Implements the accelerometer-gyrometer measurements.
Definition accelerometer-gyrometer.hpp:36
This is the base class of any functor that describes the dynamics of the state and the measurement....
Definition dynamical-system-functor-base.hpp:33
The class is an implementation of the dynamical system defined by an inertial measurement unit (IMU) ...
Definition imu-dynamical-system.hpp:35
bool withGyroBias_
Definition imu-dynamical-system.hpp:110
double dt_
Definition imu-dynamical-system.hpp:98
virtual Index getStateSize() const
Gets the state size.
virtual NoiseBase * getMeasurementNoise() const
Gets a pointer on the measurement noise.
virtual void setMeasurementNoise(NoiseBase *)
Sets a noise which disturbs the measurements.
virtual Vector stateDynamics(const Vector &x, const Vector &u, TimeIndex k)
Description of the state dynamics.
virtual void resetProcessNoise()
Removes the process noise.
virtual Vector measureDynamics(const Vector &x, const Vector &u, TimeIndex k)
Description of the sensor's dynamics.
Quaternion computeQuaternion_(const Vector3 &x)
QuaternionUnaligned quaternion_
Definition imu-dynamical-system.hpp:101
virtual void resetMeasurementNoise()
Removes the measurement noise.
virtual Index getInputSize() const
Gets the input size.
NoiseBase * processNoise_
Definition imu-dynamical-system.hpp:96
void setWithGyroBias(bool)
Set whether we use Gyro Bias.
Index statesize_
the state size may be bigger if the bias is considered
Definition imu-dynamical-system.hpp:106
virtual NoiseBase * getProcessNoise() const
Gets the process noise.
virtual void setProcessNoise(NoiseBase *)
Sets a noise which disturbs the state dynamics.
virtual void setSamplingPeriod(double dt)
Set the period of the time discretization.
Vector3Unaligned orientationVector_
Definition imu-dynamical-system.hpp:100
AccelerometerGyrometer sensor_
Definition imu-dynamical-system.hpp:94
virtual ~IMUDynamicalSystem()
The virtual destructor.
virtual Index getMeasurementSize() const
Gets the measurement size.
void updatestatesize()
Definition imu-dynamical-system.hpp:76
IMUDynamicalSystem(bool withGyroBias=false)
The constructor.
Definition noise-base.hpp:29
Definition bidim-elastic-inv-pendulum-dyn-sys.hpp:21
Eigen::Quaterniond Quaternion
Quaternion.
Definition definitions.hpp:127
long int TimeIndex
Definition definitions.hpp:139
Eigen::Vector3d Vector3
3D vector
Definition definitions.hpp:85
Eigen::Matrix< double, 3, 1, Eigen::DontAlign > Vector3Unaligned
3D vector unaligned
Definition definitions.hpp:88
Eigen::Index Index
Definition definitions.hpp:138
Eigen::VectorXd Vector
Dynamic sized scalar vector.
Definition definitions.hpp:76
Eigen::Quaternion< double, Eigen::DontAlign > QuaternionUnaligned
Quaternion Unaligned.
Definition definitions.hpp:130
Implements integrators for the kinematics, in terms or rotations and translations.
Definition imu-dynamical-system.hpp:89
Definition rigid-body-kinematics.hpp:320