Biorbd
|
Class Kinematic reconstruction algorithm using an Extended Kalman Filter using skin markers. More...
#include <KalmanReconsMarkers.h>
Public Member Functions | |
KalmanReconsMarkers () | |
Initialize the Kalman filter and Kalman reconstruction for Markers data. | |
KalmanReconsMarkers (biorbd::Model &model, biorbd::rigidbody::KalmanParam params=biorbd::rigidbody::KalmanParam()) | |
Initialize the Kalman filter and Kalman reconstruction for Markers data. More... | |
biorbd::rigidbody::KalmanReconsMarkers | DeepCopy () const |
Deep copy of the Kalman reconstruction. More... | |
void | DeepCopy (const biorbd::rigidbody::KalmanReconsMarkers &other) |
Deep copy of the Kalman reconstruction. More... | |
virtual void | reconstructFrame (biorbd::Model &model, const biorbd::rigidbody::Markers &Tobs, biorbd::rigidbody::GeneralizedCoordinates *Q, biorbd::rigidbody::GeneralizedVelocity *Qdot, biorbd::rigidbody::GeneralizedAcceleration *Qddot, bool removeAxes=true) |
Reconstruct the kinematics from markers data. More... | |
virtual void | reconstructFrame (biorbd::Model &model, const std::vector< biorbd::rigidbody::NodeSegment > &Tobs, biorbd::rigidbody::GeneralizedCoordinates *Q, biorbd::rigidbody::GeneralizedVelocity *Qdot, biorbd::rigidbody::GeneralizedAcceleration *Qddot, bool removeAxes=true) |
Reconstruct the kinematics from markers data. More... | |
virtual void | reconstructFrame (biorbd::Model &model, const biorbd::utils::Vector &Tobs, biorbd::rigidbody::GeneralizedCoordinates *Q=nullptr, biorbd::rigidbody::GeneralizedVelocity *Qdot=nullptr, biorbd::rigidbody::GeneralizedAcceleration *Qddot=nullptr, bool removeAxes=true) |
Reconstruct the kinematics from markers data. More... | |
virtual void | reconstructFrame () |
This function cannot be used to reconstruct frames. | |
bool | first () |
Return if the first iteration was done. More... | |
![]() | |
KalmanRecons () | |
Kalman reconstruction. | |
KalmanRecons (biorbd::Model &model, unsigned int nbMeasure, KalmanParam params=KalmanParam()) | |
Kalman reconstruction. More... | |
virtual | ~KalmanRecons () |
Destroy class properly. | |
void | DeepCopy (const biorbd::rigidbody::KalmanRecons &other) |
Deep copy of Kalman reconstruction. More... | |
void | getState (biorbd::rigidbody::GeneralizedCoordinates *Q=nullptr, biorbd::rigidbody::GeneralizedVelocity *Qdot=nullptr, biorbd::rigidbody::GeneralizedAcceleration *Qddot=nullptr) |
Get the state (Q, Qdot, Qddot) More... | |
void | setInitState (const biorbd::rigidbody::GeneralizedCoordinates *Q=nullptr, const biorbd::rigidbody::GeneralizedVelocity *Qdot=nullptr, const biorbd::rigidbody::GeneralizedAcceleration *Qddot=nullptr) |
Set the initial guess of the reconstruction. More... | |
Protected Member Functions | |
virtual void | initialize () |
Initialization of the filter. | |
virtual void | manageOcclusionDuringIteration (biorbd::utils::Matrix &InvTp, biorbd::utils::Vector &measure, const std::vector< unsigned int > &occlusion) |
Manage the occlusion during the iteration. More... | |
![]() | |
biorbd::utils::Matrix | evolutionMatrix (const unsigned int m, unsigned int n, double Te) |
Create the evolution matrix. More... | |
biorbd::utils::Matrix | processNoiseMatrix (const unsigned int nbQ, double Te) |
Process the noise matrix. More... | |
biorbd::utils::Matrix | measurementNoiseMatrix (const unsigned int nbT, double val) |
Matrix of the noise on the measurements. More... | |
biorbd::utils::Matrix | initCovariance (const unsigned int nbQ, double val) |
Returns a initialized covianriance matrix. More... | |
biorbd::rigidbody::GeneralizedCoordinates | initState (const unsigned int nbQ) |
Initialize the states. More... | |
void | iteration (biorbd::utils::Vector measure, const biorbd::utils::Vector &projectedMeasure, const biorbd::utils::Matrix &Hessian, const std::vector< unsigned int > &occlusion=std::vector< unsigned int >()) |
Compute an iteration of the Kalman filter. More... | |
Protected Attributes | |
std::shared_ptr< biorbd::utils::Matrix > | m_PpInitial |
Initial covariance matrix. | |
std::shared_ptr< bool > | m_firstIteration |
If first iteration was done. | |
![]() | |
std::shared_ptr< KalmanParam > | m_params |
The parameters of the Kalman filter. | |
std::shared_ptr< double > | m_Te |
Inherent parameter to the frequency. | |
std::shared_ptr< unsigned int > | m_nbDof |
Number of states. | |
std::shared_ptr< unsigned int > | m_nMeasure |
Number of measurements. | |
std::shared_ptr< biorbd::utils::Vector > | m_xp |
State vector. | |
std::shared_ptr< biorbd::utils::Matrix > | m_A |
Evolution matrix. | |
std::shared_ptr< biorbd::utils::Matrix > | m_Q |
Noise matrix. | |
std::shared_ptr< biorbd::utils::Matrix > | m_R |
Matrix of the noise on the measurements. | |
std::shared_ptr< biorbd::utils::Matrix > | m_Pp |
Covariance matrix. | |
Class Kinematic reconstruction algorithm using an Extended Kalman Filter using skin markers.
Definition at line 16 of file KalmanReconsMarkers.h.
biorbd::rigidbody::KalmanReconsMarkers::KalmanReconsMarkers | ( | biorbd::Model & | model, |
biorbd::rigidbody::KalmanParam | params = biorbd::rigidbody::KalmanParam() |
||
) |
Initialize the Kalman filter and Kalman reconstruction for Markers data.
model | The joint model |
params | The Kalman filter parameters |
Definition at line 22 of file KalmanReconsMarkers.cpp.
biorbd::rigidbody::KalmanReconsMarkers biorbd::rigidbody::KalmanReconsMarkers::DeepCopy | ( | ) | const |
Deep copy of the Kalman reconstruction.
Definition at line 35 of file KalmanReconsMarkers.cpp.
void biorbd::rigidbody::KalmanReconsMarkers::DeepCopy | ( | const biorbd::rigidbody::KalmanReconsMarkers & | other | ) |
Deep copy of the Kalman reconstruction.
other | The Kalman reconstruction to copy |
Definition at line 42 of file KalmanReconsMarkers.cpp.
bool biorbd::rigidbody::KalmanReconsMarkers::first | ( | ) |
Return if the first iteration was done.
Definition at line 68 of file KalmanReconsMarkers.cpp.
|
protectedvirtual |
Manage the occlusion during the iteration.
InvTp | The inverse of the Tp matrix |
measure | The vector actual measurement to track |
occlusion | The vector where occlusions occurs |
Reimplemented from biorbd::rigidbody::KalmanRecons.
Definition at line 56 of file KalmanReconsMarkers.cpp.
|
virtual |
Reconstruct the kinematics from markers data.
model | The joint model |
Tobs | The observed markers |
Q | The generalized coordinates |
Qdot | The generalized velocities |
Qddot | The generalized accelerations |
removeAxes | If the algo should ignore or not the removeAxis defined in the bioMod file |
Definition at line 73 of file KalmanReconsMarkers.cpp.
|
virtual |
Reconstruct the kinematics from markers data.
model | The joint model |
Tobs | The observed markers in a column-major vector |
Q | The generalized coordinates |
Qdot | The generalized velocities |
Qddot | The generalized accelerations |
removeAxes | If the algo should ignore or not the removeAxis defined in the bioMod file |
Definition at line 106 of file KalmanReconsMarkers.cpp.
|
virtual |
Reconstruct the kinematics from markers data.
model | The joint model |
Tobs | The observed markers |
Q | The generalized coordinates |
Qdot | The generalized velocities |
Qddot | The generalized accelerations |
removeAxes | If the algo should ignore or not the removeAxis defined in the bioMod file |
Definition at line 89 of file KalmanReconsMarkers.cpp.