stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem Class Reference

This class describes the dynamics of a robot's flexibility this dynamics with elastic forces to bring the contacts at their position in the environment. More...

#include <state-observation/flexibility-estimation/imu-elastic-local-frame-dynamical-system.hpp>

Inheritance diagram for stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem:
Collaboration diagram for stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem:

Classes

struct  contactModel
 
struct  input
 
struct  Optimization
 
struct  state
 

Public Types

typedef Eigen::LLT< Matrix3LLTMatrix3
 

Public Member Functions

 IMUElasticLocalFrameDynamicalSystem (double dt)
 constructor More...
 
virtual ~IMUElasticLocalFrameDynamicalSystem ()
 virtual destructor More...
 
void test ()
 
void computeContactWrench (const Matrix3 &orientation, const Vector3 &position, const IndexedVectorArray &contactPosV, const IndexedVectorArray &contactOriV, const Vector &fc, const Vector &tc, const Vector3 &fm, const Vector3 &tm, const Vector3 &addForce, const Vector3 &addMoment)
 
stateObservation::Vector computeAccelerations (const Vector &x, const Vector &u)
 
virtual void computeAccelerations (const Vector3 &positionCom, const Vector3 &velocityCom, const Vector3 &accelerationCom, const Vector3 &AngMomentum, const Vector3 &dotAngMomentum, const Matrix3 &Inertia, const Matrix3 &dotInertia, const IndexedVectorArray &contactPos, const IndexedVectorArray &contactOri, const Vector3 &position, const Vector3 &linVelocity, Vector3 &linearAcceleration, const Vector3 &oriVector, const Matrix3 &orientation, const Vector3 &angularVel, Vector3 &angularAcceleration, const Vector &fc, const Vector &tc, const Vector3 &fm, const Vector3 &tm, const Vector3 &addForces, const Vector3 &addMoments)
 
virtual stateObservation::Vector stateDynamics (const stateObservation::Vector &x, const stateObservation::Vector &u, TimeIndex k)
 Description of the state dynamics. More...
 
stateObservation::Matrix stateDynamicsJacobian ()
 compute the jacobien of the state dynamics at the last computed value More...
 
stateObservation::Matrix stateDynamicsJacobian (const stateObservation::Vector &x, const stateObservation::Vector &u, TimeIndex k)
 compute the jacobien of the state dynamics at a given state More...
 
void setFDstep (const stateObservation::Vector &dx)
 sets the finite differences derivation step vector More...
 
virtual stateObservation::Vector measureDynamics (const stateObservation::Vector &x, const stateObservation::Vector &u, TimeIndex k)
 Description of the sensor's dynamics. More...
 
stateObservation::Matrix measureDynamicsJacobian ()
 compute the Jacobien of the measurements dynamics at the last computed value More...
 
stateObservation::Matrix measureDynamicsJacobian (const stateObservation::Vector &x, const stateObservation::Vector &u, TimeIndex k)
 compute the Jacobien of the measurements dynamics at a given state value More...
 
virtual void setProcessNoise (stateObservation::NoiseBase *)
 Sets a noise which disturbs the state dynamics. More...
 
virtual void resetProcessNoise ()
 Removes the process noise. More...
 
virtual stateObservation::NoiseBasegetProcessNoise () const
 Gets the process noise. More...
 
virtual void setMeasurementNoise (stateObservation::NoiseBase *)
 Sets a noise which disturbs the measurements. More...
 
virtual void resetMeasurementNoise ()
 Removes the measurement noise. More...
 
virtual stateObservation::NoiseBasegetMeasurementNoise () 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 void setInputSize (Index i)
 Sets the input size. More...
 
virtual Index getMeasurementSize () const
 Gets the contacts position. More...
 
virtual void setContactsNumber (unsigned)
 Sets the number of contacts. More...
 
virtual void setPe (stateObservation::Vector3 Pe)
 
unsigned getContactsNumber (void) const
 Gets the nimber of contacts. More...
 
virtual void setContactModel (unsigned nb)
 
virtual void setPrinted (bool b)
 
virtual void computeElastContactForcesAndMoments (const IndexedVectorArray &contactPosArray, const IndexedVectorArray &contactOriArray, const IndexedVectorArray &contactVelArray, const IndexedVectorArray &contactAngVelArray, const Vector3 &position, const Vector3 &linVelocity, const Vector3 &oriVector, const Matrix3 &orientation, const Vector3 &angVel, Vector &fc, Vector &tc)
 
virtual void computeElastPendulumForcesAndMoments (const IndexedVectorArray &PrArray, const Vector3 &position, const Vector3 &linVelocity, const Vector3 &oriVector, const Matrix3 &orientation, const Vector3 &angVel, Vector &forces, Vector &moments)
 
void computeForcesAndMoments (const IndexedVectorArray &position1, const IndexedVectorArray &position2, const IndexedVectorArray &velocity1, const IndexedVectorArray &velocity2, const Vector3 &position, const Vector3 &linVelocity, const Vector3 &oriVector, const Matrix3 &orientation, const Vector3 &angVel, Vector &fc, Vector &tc)
 
virtual void computeForcesAndMoments (const Vector &x, const Vector &u)
 
virtual Vector getForcesAndMoments ()
 
virtual Vector getForcesAndMoments (const Vector &x, const Vector &u)
 
virtual Vector getMomentaDotFromForces (const Vector &x, const Vector &u)
 
virtual Vector getMomentaDotFromKinematics (const Vector &x, const Vector &u)
 
virtual void iterateDynamicsEuler (const Vector3 &positionCom, const Vector3 &velocityCom, const Vector3 &accelerationCom, const Vector3 &AngMomentum, const Vector3 &dotAngMomentum, const Matrix3 &Inertia, const Matrix3 &dotInertia, const IndexedVectorArray &contactPos, const IndexedVectorArray &contactOri, Vector3 &position, Vector3 &linVelocity, Vector &fc1, Vector3 &oriVector, Vector3 &angularVel, Vector &fc2, const Vector3 &fm, const Vector3 &tm, const Vector3 &addForces, const Vector3 &addMoments, double dt)
 
virtual void iterateDynamicsRK4 (const Vector3 &positionCom, const Vector3 &velocityCom, const Vector3 &accelerationCom, const Vector3 &AngMomentum, const Vector3 &dotAngMomentum, const Matrix3 &Inertia, const Matrix3 &dotInertia, const IndexedVectorArray &contactPos, const IndexedVectorArray &contactOri, Vector3 &position, Vector3 &linVelocity, Vector &fc1, Vector3 &oriVector, Vector3 &angularVel, Vector &fc2, const Vector3 &fm, const Vector3 &tm, const Vector3 &addForces, const Vector3 &addMoments, double dt)
 
virtual void setWithForceMeasurements (bool b)
 
virtual bool getWithForceMeasurements () const
 
virtual void setWithComBias (bool b)
 
virtual bool getWithComBias () const
 
virtual void setWithAbsolutePosition (bool b)
 
virtual bool getWithAbsolutePosition () const
 
void setWithUnmodeledForces (bool b)
 
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 Matrix getKfe () const
 
virtual Matrix getKfv () const
 
virtual Matrix getKte () const
 
virtual Matrix getKtv () const
 
virtual void setRobotMass (double d)
 
virtual double getRobotMass () const
 
- 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

void updateMeasurementSize_ ()
 
Matrix3computeRotation_ (const Vector3 &x, int i)
 
- Protected Member Functions inherited from stateObservation::DynamicalSystemFunctorBase
void assertStateVector_ (const Vector &v)
 
void assertInputVector_ (const Vector &v)
 

Protected Attributes

bool printed_
 
stateObservation::AccelerometerGyrometer sensor_
 
stateObservation::NoiseBaseprocessNoise_
 
double dt_
 
double robotMass_
 
double robotMassInv_
 
Index inputSize_
 
unsigned nbContacts_
 
unsigned contactModel_
 
Vector fc_
 
Vector tc_
 
Vector dx_
 
Vector xk1_
 
Vector xk_
 
Vector uk_
 
Vector xk_fory_
 
Vector yk_
 
Vector uk_fory_
 
Index measurementSize_
 
std::vector< Vector3, Eigen::aligned_allocator< Vector3 > > contactPositions_
 
Matrix3 Kfe_
 
Matrix3 Kte_
 
Matrix3 Kfv_
 
Matrix3 Ktv_
 
Matrix3 KfeRopes_
 
Matrix3 KteRopes_
 
Matrix3 KfvRopes_
 
Matrix3 KtvRopes_
 
TimeIndex kcurrent_
 
bool withForceMeasurements_
 
bool withComBias_
 
bool withAbsolutePos_
 
bool withUnmodeledForces_
 
stateObservation::Vector3 pe
 
double marginalStabilityFactor_
 
unsigned index_
 
struct stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::Optimization op_
 

Static Protected Attributes

static constexpr Index stateSize_ = state::size
 
static constexpr Index measurementSizeBase_ = 6
 

Detailed Description

This class describes the dynamics of a robot's flexibility this dynamics with elastic forces to bring the contacts at their position in the environment.

Member Typedef Documentation

◆ LLTMatrix3

Constructor & Destructor Documentation

◆ IMUElasticLocalFrameDynamicalSystem()

stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::IMUElasticLocalFrameDynamicalSystem ( double  dt)
explicit

constructor

◆ ~IMUElasticLocalFrameDynamicalSystem()

virtual stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::~IMUElasticLocalFrameDynamicalSystem ( )
virtual

virtual destructor

Member Function Documentation

◆ computeAccelerations() [1/2]

stateObservation::Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::computeAccelerations ( const Vector x,
const Vector u 
)

◆ computeAccelerations() [2/2]

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::computeAccelerations ( const Vector3 positionCom,
const Vector3 velocityCom,
const Vector3 accelerationCom,
const Vector3 AngMomentum,
const Vector3 dotAngMomentum,
const Matrix3 Inertia,
const Matrix3 dotInertia,
const IndexedVectorArray contactPos,
const IndexedVectorArray contactOri,
const Vector3 position,
const Vector3 linVelocity,
Vector3 linearAcceleration,
const Vector3 oriVector,
const Matrix3 orientation,
const Vector3 angularVel,
Vector3 angularAcceleration,
const Vector fc,
const Vector tc,
const Vector3 fm,
const Vector3 tm,
const Vector3 addForces,
const Vector3 addMoments 
)
virtual

◆ computeContactWrench()

void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::computeContactWrench ( const Matrix3 orientation,
const Vector3 position,
const IndexedVectorArray contactPosV,
const IndexedVectorArray contactOriV,
const Vector fc,
const Vector tc,
const Vector3 fm,
const Vector3 tm,
const Vector3 addForce,
const Vector3 addMoment 
)

◆ computeElastContactForcesAndMoments()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::computeElastContactForcesAndMoments ( const IndexedVectorArray contactPosArray,
const IndexedVectorArray contactOriArray,
const IndexedVectorArray contactVelArray,
const IndexedVectorArray contactAngVelArray,
const Vector3 position,
const Vector3 linVelocity,
const Vector3 oriVector,
const Matrix3 orientation,
const Vector3 angVel,
Vector fc,
Vector tc 
)
virtual

◆ computeElastPendulumForcesAndMoments()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::computeElastPendulumForcesAndMoments ( const IndexedVectorArray PrArray,
const Vector3 position,
const Vector3 linVelocity,
const Vector3 oriVector,
const Matrix3 orientation,
const Vector3 angVel,
Vector forces,
Vector moments 
)
virtual

◆ computeForcesAndMoments() [1/2]

void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::computeForcesAndMoments ( const IndexedVectorArray position1,
const IndexedVectorArray position2,
const IndexedVectorArray velocity1,
const IndexedVectorArray velocity2,
const Vector3 position,
const Vector3 linVelocity,
const Vector3 oriVector,
const Matrix3 orientation,
const Vector3 angVel,
Vector fc,
Vector tc 
)

◆ computeForcesAndMoments() [2/2]

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::computeForcesAndMoments ( const Vector x,
const Vector u 
)
virtual

◆ computeRotation_()

Matrix3& stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::computeRotation_ ( const Vector3 x,
int  i 
)
protected

◆ getContactsNumber()

unsigned stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getContactsNumber ( void  ) const
inline

Gets the nimber of contacts.

◆ getForcesAndMoments() [1/2]

virtual Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getForcesAndMoments ( )
virtual

◆ getForcesAndMoments() [2/2]

virtual Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getForcesAndMoments ( const Vector x,
const Vector u 
)
virtual

◆ getInputSize()

virtual Index stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getInputSize ( ) const
virtual

Gets the input size.

Implements stateObservation::DynamicalSystemFunctorBase.

◆ getKfe()

virtual Matrix stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getKfe ( ) const
virtual

◆ getKfv()

virtual Matrix stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getKfv ( ) const
virtual

◆ getKte()

virtual Matrix stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getKte ( ) const
virtual

◆ getKtv()

virtual Matrix stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getKtv ( ) const
virtual

◆ getMeasurementNoise()

virtual stateObservation::NoiseBase* stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getMeasurementNoise ( ) const
virtual

Gets a pointer on the measurement noise.

◆ getMeasurementSize()

virtual Index stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getMeasurementSize ( ) const
virtual

Gets the contacts position.

Gets the contact number virtual Gets the measurement size

Implements stateObservation::DynamicalSystemFunctorBase.

◆ getMomentaDotFromForces()

virtual Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getMomentaDotFromForces ( const Vector x,
const Vector u 
)
virtual

◆ getMomentaDotFromKinematics()

virtual Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getMomentaDotFromKinematics ( const Vector x,
const Vector u 
)
virtual

◆ getProcessNoise()

virtual stateObservation::NoiseBase* stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getProcessNoise ( ) const
virtual

Gets the process noise.

◆ getRobotMass()

virtual double stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getRobotMass ( ) const
virtual

◆ getStateSize()

virtual Index stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getStateSize ( ) const
virtual

Gets the state size.

Implements stateObservation::DynamicalSystemFunctorBase.

◆ getWithAbsolutePosition()

virtual bool stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getWithAbsolutePosition ( ) const
virtual

◆ getWithComBias()

virtual bool stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getWithComBias ( ) const
virtual

◆ getWithForceMeasurements()

virtual bool stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::getWithForceMeasurements ( ) const
virtual

◆ iterateDynamicsEuler()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::iterateDynamicsEuler ( const Vector3 positionCom,
const Vector3 velocityCom,
const Vector3 accelerationCom,
const Vector3 AngMomentum,
const Vector3 dotAngMomentum,
const Matrix3 Inertia,
const Matrix3 dotInertia,
const IndexedVectorArray contactPos,
const IndexedVectorArray contactOri,
Vector3 position,
Vector3 linVelocity,
Vector fc1,
Vector3 oriVector,
Vector3 angularVel,
Vector fc2,
const Vector3 fm,
const Vector3 tm,
const Vector3 addForces,
const Vector3 addMoments,
double  dt 
)
virtual

◆ iterateDynamicsRK4()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::iterateDynamicsRK4 ( const Vector3 positionCom,
const Vector3 velocityCom,
const Vector3 accelerationCom,
const Vector3 AngMomentum,
const Vector3 dotAngMomentum,
const Matrix3 Inertia,
const Matrix3 dotInertia,
const IndexedVectorArray contactPos,
const IndexedVectorArray contactOri,
Vector3 position,
Vector3 linVelocity,
Vector fc1,
Vector3 oriVector,
Vector3 angularVel,
Vector fc2,
const Vector3 fm,
const Vector3 tm,
const Vector3 addForces,
const Vector3 addMoments,
double  dt 
)
virtual

◆ measureDynamics()

virtual stateObservation::Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::measureDynamics ( const stateObservation::Vector x,
const stateObservation::Vector u,
TimeIndex  k 
)
virtual

Description of the sensor's dynamics.

Implements stateObservation::DynamicalSystemFunctorBase.

◆ measureDynamicsJacobian() [1/2]

stateObservation::Matrix stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::measureDynamicsJacobian ( )

compute the Jacobien of the measurements dynamics at the last computed value

◆ measureDynamicsJacobian() [2/2]

stateObservation::Matrix stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::measureDynamicsJacobian ( const stateObservation::Vector x,
const stateObservation::Vector u,
TimeIndex  k 
)

compute the Jacobien of the measurements dynamics at a given state value

◆ resetMeasurementNoise()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::resetMeasurementNoise ( )
virtual

Removes the measurement noise.

◆ resetProcessNoise()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::resetProcessNoise ( )
virtual

Removes the process noise.

◆ setContactModel()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setContactModel ( unsigned  nb)
virtual

◆ setContactsNumber()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setContactsNumber ( unsigned  )
virtual

Sets the number of contacts.

◆ setFDstep()

void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setFDstep ( const stateObservation::Vector dx)

sets the finite differences derivation step vector

◆ setInputSize()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setInputSize ( Index  i)
virtual

Sets the input size.

◆ setKfe()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setKfe ( const Matrix3 m)
virtual

◆ setKfeRopes()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setKfeRopes ( const Matrix3 m)
virtual

◆ setKfv()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setKfv ( const Matrix3 m)
virtual

◆ setKfvRopes()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setKfvRopes ( const Matrix3 m)
virtual

◆ setKte()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setKte ( const Matrix3 m)
virtual

◆ setKteRopes()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setKteRopes ( const Matrix3 m)
virtual

◆ setKtv()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setKtv ( const Matrix3 m)
virtual

◆ setKtvRopes()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setKtvRopes ( const Matrix3 m)
virtual

◆ setMeasurementNoise()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setMeasurementNoise ( stateObservation::NoiseBase )
virtual

Sets a noise which disturbs the measurements.

◆ setPe()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setPe ( stateObservation::Vector3  Pe)
inlinevirtual

◆ setPrinted()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setPrinted ( bool  b)
inlinevirtual

◆ setProcessNoise()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setProcessNoise ( stateObservation::NoiseBase )
virtual

Sets a noise which disturbs the state dynamics.

◆ setRobotMass()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setRobotMass ( double  d)
virtual

◆ setSamplingPeriod()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setSamplingPeriod ( double  dt)
virtual

Set the period of the time discretization.

◆ setWithAbsolutePosition()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setWithAbsolutePosition ( bool  b)
virtual

◆ setWithComBias()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setWithComBias ( bool  b)
virtual

◆ setWithForceMeasurements()

virtual void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setWithForceMeasurements ( bool  b)
virtual

◆ setWithUnmodeledForces()

void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::setWithUnmodeledForces ( bool  b)

◆ stateDynamics()

virtual stateObservation::Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::stateDynamics ( const stateObservation::Vector x,
const stateObservation::Vector u,
TimeIndex  k 
)
virtual

Description of the state dynamics.

Implements stateObservation::DynamicalSystemFunctorBase.

◆ stateDynamicsJacobian() [1/2]

stateObservation::Matrix stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::stateDynamicsJacobian ( )

compute the jacobien of the state dynamics at the last computed value

◆ stateDynamicsJacobian() [2/2]

stateObservation::Matrix stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::stateDynamicsJacobian ( const stateObservation::Vector x,
const stateObservation::Vector u,
TimeIndex  k 
)

compute the jacobien of the state dynamics at a given state

◆ test()

void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::test ( )

◆ updateMeasurementSize_()

void stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::updateMeasurementSize_ ( )
protected

Member Data Documentation

◆ contactModel_

unsigned stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::contactModel_
protected

◆ contactPositions_

std::vector<Vector3, Eigen::aligned_allocator<Vector3> > stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::contactPositions_
protected

◆ dt_

double stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::dt_
protected

◆ dx_

Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::dx_
protected

◆ fc_

Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::fc_
protected

◆ index_

unsigned stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::index_
protected

◆ inputSize_

Index stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::inputSize_
protected

◆ kcurrent_

TimeIndex stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::kcurrent_
protected

◆ Kfe_

Matrix3 stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::Kfe_
protected

◆ KfeRopes_

Matrix3 stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::KfeRopes_
protected

◆ Kfv_

Matrix3 stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::Kfv_
protected

◆ KfvRopes_

Matrix3 stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::KfvRopes_
protected

◆ Kte_

Matrix3 stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::Kte_
protected

◆ KteRopes_

Matrix3 stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::KteRopes_
protected

◆ Ktv_

Matrix3 stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::Ktv_
protected

◆ KtvRopes_

Matrix3 stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::KtvRopes_
protected

◆ marginalStabilityFactor_

double stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::marginalStabilityFactor_
protected

◆ measurementSize_

Index stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::measurementSize_
protected

◆ measurementSizeBase_

constexpr Index stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::measurementSizeBase_ = 6
staticconstexprprotected

◆ nbContacts_

unsigned stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::nbContacts_
protected

◆ op_

struct stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::Optimization stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::op_
protected

◆ pe

stateObservation::Vector3 stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::pe
protected

◆ printed_

bool stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::printed_
protected

◆ processNoise_

stateObservation::NoiseBase* stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::processNoise_
protected

◆ robotMass_

double stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::robotMass_
protected

◆ robotMassInv_

double stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::robotMassInv_
protected

◆ sensor_

stateObservation::AccelerometerGyrometer stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::sensor_
protected

◆ stateSize_

constexpr Index stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::stateSize_ = state::size
staticconstexprprotected

◆ tc_

Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::tc_
protected

◆ uk_

Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::uk_
protected

◆ uk_fory_

Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::uk_fory_
protected

◆ withAbsolutePos_

bool stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::withAbsolutePos_
protected

◆ withComBias_

bool stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::withComBias_
protected

◆ withForceMeasurements_

bool stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::withForceMeasurements_
protected

◆ withUnmodeledForces_

bool stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::withUnmodeledForces_
protected

◆ xk1_

Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::xk1_
protected

◆ xk_

Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::xk_
protected

◆ xk_fory_

Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::xk_fory_
protected

◆ yk_

Vector stateObservation::flexibilityEstimation::IMUElasticLocalFrameDynamicalSystem::yk_
protected

The documentation for this class was generated from the following file: