BipedalLocomotion::Estimators::RobotDynamicsEstimator::JointVelocityStateDynamics class

The JointVelocityDynamics class is a concrete implementation of the Dynamics.

Please use this element if you want to use the robot dynamic model to update the joint dynamics. The JointVelocityDynamics represents the following equation in the continuous time:

\[ \ddot{s} = H^{-1} [\tau_{m} - \tau_{F} + (\sum J^T_{FT} f_{FT}) + + (\sum J^T_{ext} f_{ext}) - F^T {}^B \dot v - h ] \]

where \ddot{s} is given as an input to this class. The discretized model becomes:

\[ \dot{s}_{k+1} = \dot{s}_{k} + \Delta T \ddot{s}_{k} \]

Base classes

class Dynamics
The class Dynamics represents a base class describing a generic model composing the ukf process model or the ukf measurement model.

Constructors, destructors, conversion operators

JointVelocityStateDynamics()
~JointVelocityStateDynamics() virtual

Public functions

auto setSubModels(const std::vector<SubModel>& subModelList, const std::vector<std::shared_ptr<KinDynWrapper>>& kinDynWrapperList) -> bool override
Set the KinDynWrapper object.
auto initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> paramHandler, const std::string& name) -> bool override
Initialize the state dynamics.
auto finalize(const System::VariablesHandler& stateVariableHandler) -> bool override
Finalize the Dynamics.
auto checkStateVariableHandler() -> bool override
Controls whether the variable handler contains the variables on which the dynamics depend.
auto update() -> bool override
Update the state.
void setState(const Eigen::Ref<const Eigen::VectorXd> ukfState) override
Set the state of the ukf needed to update the dynamics of the state variable associated to ths object.
void setInput(const UKFInput& ukfInput) override
Set a UKFInput object.

Function documentation

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::JointVelocityStateDynamics::setSubModels(const std::vector<SubModel>& subModelList, const std::vector<std::shared_ptr<KinDynWrapper>>& kinDynWrapperList) override

Set the KinDynWrapper object.

Parameters
subModelList list of SubModel objects
kinDynWrapperList list of pointers to KinDynWrapper objects.
Returns True in case of success, false otherwise.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::JointVelocityStateDynamics::initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> paramHandler, const std::string& name) override

Initialize the state dynamics.

Parameters
paramHandler pointer to the parameters handler.
name name of the dynamics.
Returns True in case of success, false otherwise.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::JointVelocityStateDynamics::finalize(const System::VariablesHandler& stateVariableHandler) override

Finalize the Dynamics.

Parameters
stateVariableHandler object describing the variables in the state vector.
Returns true in case of success, false otherwise.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::JointVelocityStateDynamics::checkStateVariableHandler() override

Controls whether the variable handler contains the variables on which the dynamics depend.

Returns True in case all the dependencies are contained in the variable handler, false otherwise.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::JointVelocityStateDynamics::update() override

Update the state.

Returns True in case of success, false otherwise.

void BipedalLocomotion::Estimators::RobotDynamicsEstimator::JointVelocityStateDynamics::setState(const Eigen::Ref<const Eigen::VectorXd> ukfState) override

Set the state of the ukf needed to update the dynamics of the state variable associated to ths object.

Parameters
ukfState reference to the ukf state.

void BipedalLocomotion::Estimators::RobotDynamicsEstimator::JointVelocityStateDynamics::setInput(const UKFInput& ukfInput) override

Set a UKFInput object.

Parameters
ukfInput reference to the UKFInput struct.