This class implements the flexibility estimation of a robot with the hypothesis that the contact positions do not move. This constraint is expressed using fictious measurements but the interface is transparent to this assumption, the state is expressed using classical representation of position, velocity, acceleration, orientation (using (theta x mu) representation) angular velocity (omega) and acceleration (omega dot) More...
#include <state-observation/flexibility-estimation/model-base-ekf-flex-estimator-imu.hpp>
Classes | |
struct | contactModel |
struct | optimization |
Public Member Functions | |
ModelBaseEKFFlexEstimatorIMU (double dt=0.005) | |
The constructor, it requires the value of the time discretization period. More... | |
virtual | ~ModelBaseEKFFlexEstimatorIMU () |
Virtual destructor. More... | |
void | setContactsNumber (unsigned i) |
Sets the number of contacts can be changed online. More... | |
unsigned | getContactsNumber () |
IMUElasticLocalFrameDynamicalSystem | getFunctor () |
virtual stateObservation::Vector | computeAccelerations () |
void | setContactModel (unsigned nb) |
virtual void | setMeasurement (const Vector &y) |
Sets the value of the next sensor measurement y_{k+1}. More... | |
virtual void | setProcessNoiseCovariance (const Matrix &Q) |
Sets the process covariance matrice. More... | |
virtual void | setMeasurementNoiseCovariance (const Matrix &R) |
Sets the measurements covariance matrice. More... | |
virtual Matrix | getProcessNoiseCovariance () const |
gets the covariance matrices for the process noises More... | |
virtual Matrix | getMeasurementNoiseCovariance () const |
gets the covariance matrices for the sensor noises More... | |
virtual Vector | getMomentaDotFromForces () |
virtual Vector | getMomentaDotFromKinematics () |
virtual Vector | getForcesAndMoments () |
stateObservation::Vector | getStateCovariance () const |
virtual void | setComBiasGuess (const stateObservation::Vector &x) |
virtual void | setFlexibilityGuess (const Matrix &x) |
virtual Matrix4 | getFlexibility () |
Gets an estimation of the flexibility in the form of a homogeneous matrix. More... | |
virtual const Vector & | getFlexibilityVector () |
Gets an estimation of the flexibility in the form of a state vector \hat{x_{k+1}}. More... | |
virtual stateObservation::Matrix & | computeLocalObservationMatrix () |
virtual stateObservation::Matrix | getAMatrix () |
virtual stateObservation::Matrix | getCMatrix () |
virtual Index | getMeasurementSize () const |
virtual Index | getStateSize () const |
virtual Index | getInputSize () const |
virtual void | setWithForcesMeasurements (bool) |
sets to whether or not the force mesurements are taken into account More... | |
bool | getWithForcesMeasurements () |
virtual void | setWithAbsolutePos (bool) |
void | setWithUnmodeledForces (bool b) |
bool | getWithUnmodeledForces () |
bool | getWithAbsolutePos () |
virtual void | setWithComBias (bool b) |
virtual bool | getWithComBias () |
virtual void | setUnmodeledForceVariance (double d) |
virtual void | setUnmodeledForceProcessVariance (double d) |
virtual void | setForceVariance (double d) |
virtual void | setForceVariance (const Matrix3 &C) |
virtual void | setAbsolutePosVariance (double d) |
virtual void | setSamplingPeriod (double) |
sets the sampling period More... | |
void | setOn (bool &b) |
Enable or disable the estimation. More... | |
virtual void | setKfe (const Matrix3 &m) |
virtual void | setKfv (const Matrix3 &m) |
virtual void | setKte (const Matrix3 &m) |
virtual void | setKtv (const Matrix3 &m) |
virtual void | setKfeRopes (const Matrix3 &m) |
virtual void | setKfvRopes (const Matrix3 &m) |
virtual void | setKteRopes (const Matrix3 &m) |
virtual void | setKtvRopes (const Matrix3 &m) |
virtual void | setPe (const stateObservation::Vector3 &Pe) |
virtual Matrix | getKfe () const |
virtual Matrix | getKfv () const |
virtual Matrix | getKte () const |
virtual Matrix | getKtv () const |
virtual void | resetCovarianceMatrices () |
Resets the covariance matrices to their original values. More... | |
virtual void | resetStateCovarianceMatrix () |
virtual void | setRobotMass (double m) |
virtual double | getRobotMass () const |
void | setTorquesLimit (const Vector3 &v) |
void | setForcesLimit (const Vector3 &v) |
virtual stateObservation::Vector3 | getForcesLimit () const |
virtual stateObservation::Vector3 | getTorquesLimit () const |
void | setLimitOn (const bool &b) |
virtual bool | getLimitOn () const |
![]() | |
EKFFlexibilityEstimatorBase (Index stateSize, Index measurementSize, Index inputSize, const Vector &dx=Vector::Zero(0)) | |
virtual | ~EKFFlexibilityEstimatorBase () |
virtual destructor More... | |
virtual void | setFlexibilityCovariance (const Matrix &P) |
Sets the covariance matrix of the flexibility Guess. More... | |
virtual Matrix | getFlexibilityCovariance () const |
Gets the covariance matrix of the flexibility. More... | |
virtual Vector | getMeasurement () |
virtual void | setInput (const Vector &u) |
virtual void | setMeasurementInput (const Vector &u) |
virtual Vector | getInput () |
virtual Vector | getMeasurementInput () |
virtual const stateObservation::ExtendedKalmanFilter & | getEKF () const |
Gets a const reference on the extended Kalman filter. More... | |
virtual stateObservation::ExtendedKalmanFilter & | getEKF () |
Gets a reference on the extended Kalman filter. More... | |
virtual Vector | getSimulatedMeasurement () |
Gets a simulation of the. More... | |
virtual Vector | getInnovation () |
Get the last vector of inovation of the Kalman filter. More... | |
virtual Vector | getPredictedMeasurement () |
Get the simulated measurement of the predicted state. More... | |
virtual Vector | getPrediction () |
Get the predicted state. More... | |
virtual Vector | getLastPredictedMeasurement () |
Get the last simulated measurement. More... | |
virtual Vector | getLastPrediction () |
Get the last predicted state. More... | |
![]() | |
virtual | ~FlexibilityEstimatorBase () |
virtual destructor More... | |
FlexibilityEstimatorBase () | |
The constructor. More... | |
Static Public Member Functions | |
static Matrix | getDefaultQ () |
static Matrix6 | getDefaultRIMU () |
Protected Member Functions | |
virtual void | updateMeasurementCovarianceMatrix_ () |
![]() | |
virtual void | setJacobians (const Matrix &A, const Matrix &C) |
virtual void | useFiniteDifferencesJacobians (Vector dx) |
Protected Attributes | |
IMUElasticLocalFrameDynamicalSystem | functor_ |
Vector | x_ |
Matrix | R_ |
Matrix | Q_ |
Matrix | P_ |
const Index | stateSize_ |
Index | inputSize_ |
double | dt_ |
bool | on_ |
double | unmodeledForceVariance_ |
Matrix | forceVariance_ |
double | absPosVariance_ |
bool | useFTSensors_ |
bool | withAbsolutePos_ |
bool | withComBias_ |
bool | withUnmodeledForces_ |
Vector3 | limitTorques_ |
Vector3 | limitForces_ |
bool | limitOn_ |
struct stateObservation::flexibilityEstimation::ModelBaseEKFFlexEstimatorIMU::optimization | op_ |
![]() | |
stateObservation::ExtendedKalmanFilter | ekf_ |
bool | finiteDifferencesJacobians_ |
Vector | dx_ |
Vector | lastX_ |
TimeIndex | k_ |
Static Protected Attributes | |
static const Index | measurementSizeBase_ = 12 |
static const Index | inputSizeBase_ = IMUElasticLocalFrameDynamicalSystem::input::sizeBase |
This class implements the flexibility estimation of a robot with the hypothesis that the contact positions do not move. This constraint is expressed using fictious measurements but the interface is transparent to this assumption, the state is expressed using classical representation of position, velocity, acceleration, orientation (using (theta x mu) representation) angular velocity (omega) and acceleration (omega dot)
|
explicit |
The constructor, it requires the value of the time discretization period.
|
virtual |
Virtual destructor.
|
inlinevirtual |
|
virtual |
|
inlinevirtual |
|
inlinevirtual |
|
inline |
|
static |
|
static |
|
virtual |
Gets an estimation of the flexibility in the form of a homogeneous matrix.
Implements stateObservation::flexibilityEstimation::EKFFlexibilityEstimatorBase.
|
virtual |
Gets an estimation of the flexibility in the form of a state vector \hat{x_{k+1}}.
Reimplemented from stateObservation::flexibilityEstimation::EKFFlexibilityEstimatorBase.
|
virtual |
|
inlinevirtual |
|
inline |
|
virtual |
Gets the input size this method is pure virtual and reauires to be overloaded in implementation
Implements stateObservation::flexibilityEstimation::EKFFlexibilityEstimatorBase.
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
inlinevirtual |
|
virtual |
gets the covariance matrices for the sensor noises
Reimplemented from stateObservation::flexibilityEstimation::EKFFlexibilityEstimatorBase.
|
virtual |
Gets the measurements size this method is pure virtual and reauires to be overloaded in implementation
Implements stateObservation::flexibilityEstimation::EKFFlexibilityEstimatorBase.
|
virtual |
|
virtual |
|
virtual |
gets the covariance matrices for the process noises
Reimplemented from stateObservation::flexibilityEstimation::EKFFlexibilityEstimatorBase.
|
inlinevirtual |
|
inline |
|
virtual |
Gets the state size this method is pure virtual and reauires to be overloaded in implementation
Implements stateObservation::flexibilityEstimation::EKFFlexibilityEstimatorBase.
|
inlinevirtual |
|
inline |
|
inlinevirtual |
bool stateObservation::flexibilityEstimation::ModelBaseEKFFlexEstimatorIMU::getWithForcesMeasurements | ( | ) |
|
inline |
|
virtual |
Resets the covariance matrices to their original values.
Implements stateObservation::flexibilityEstimation::EKFFlexibilityEstimatorBase.
|
virtual |
|
virtual |
|
virtual |
void stateObservation::flexibilityEstimation::ModelBaseEKFFlexEstimatorIMU::setContactModel | ( | unsigned | nb | ) |
void stateObservation::flexibilityEstimation::ModelBaseEKFFlexEstimatorIMU::setContactsNumber | ( | unsigned | i | ) |
Sets the number of contacts can be changed online.
|
virtual |
Sets a value of the flexibility x_k provided from another source can be used for initialization of the estimator
Implements stateObservation::flexibilityEstimation::EKFFlexibilityEstimatorBase.
|
inline |
|
virtual |
|
virtual |
sets the force sensor variance, either with a diagonal matrix with constant diagonal, or using a 3x3 matrix
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
inline |
|
virtual |
Sets the value of the next sensor measurement y_{k+1}.
Reimplemented from stateObservation::flexibilityEstimation::EKFFlexibilityEstimatorBase.
|
virtual |
Sets the measurements covariance matrice.
Reimplemented from stateObservation::flexibilityEstimation::EKFFlexibilityEstimatorBase.
void stateObservation::flexibilityEstimation::ModelBaseEKFFlexEstimatorIMU::setOn | ( | bool & | b | ) |
Enable or disable the estimation.
|
inlinevirtual |
|
virtual |
Sets the process covariance matrice.
Reimplemented from stateObservation::flexibilityEstimation::EKFFlexibilityEstimatorBase.
|
virtual |
|
virtual |
sets the sampling period
|
inline |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
sets to whether or not the force mesurements are taken into account
void stateObservation::flexibilityEstimation::ModelBaseEKFFlexEstimatorIMU::setWithUnmodeledForces | ( | bool | b | ) |
|
protectedvirtual |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
staticprotected |
|
protected |
|
protected |
|
protected |
|
staticprotected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |