BipedalLocomotion::Estimators::RobotDynamicsEstimator::KinDynWrapper class

KinDynWrapper is a concrete class and implements a wrapper of the KinDynComputation class from iDynTree.

The class is used to take updated the sub-model kinematics and dynamics

Public functions

auto setModel(const SubModel& model) -> bool
setModel set the model and resize variables.
auto forwardDynamics(Eigen::Ref<const Eigen::VectorXd> motorTorqueAfterGearbox, Eigen::Ref<const Eigen::VectorXd> frictionTorques, Eigen::Ref<const Eigen::VectorXd> tauExt, manif::SE3d::Tangent baseAcceleration, Eigen::Ref<Eigen::VectorXd> jointAcceleration) -> bool
forwardDynamics computes the forward dynamics only for the joints.
auto forwardDynamics(Eigen::Ref<const Eigen::VectorXd> motorTorqueAfterGearbox, Eigen::Ref<const Eigen::VectorXd> frictionTorques, Eigen::Ref<const Eigen::VectorXd> tauExt, Eigen::Ref<Eigen::VectorXd> nuDot) -> bool
forwardDynamics computes the forward dynamics.
auto getNuDot() -> Eigen::Ref<const Eigen::VectorXd>
getNuDot get the base and joint accelerations computed as forward dynamics.

Function documentation

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::KinDynWrapper::setModel(const SubModel& model)

setModel set the model and resize variables.

Parameters
model a SubModel object describing the robot model.
Returns a boolean value saying if all the variables are initialized correctly.

The default frame velocity representation is BODY FIXED.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::KinDynWrapper::forwardDynamics(Eigen::Ref<const Eigen::VectorXd> motorTorqueAfterGearbox, Eigen::Ref<const Eigen::VectorXd> frictionTorques, Eigen::Ref<const Eigen::VectorXd> tauExt, manif::SE3d::Tangent baseAcceleration, Eigen::Ref<Eigen::VectorXd> jointAcceleration)

forwardDynamics computes the forward dynamics only for the joints.

Parameters
motorTorqueAfterGearbox joint motor torques.
frictionTorques joint friction torques.
tauExt torques generated by external contacts.
baseAcceleration acceleration of the base.
jointAcceleration acceleration of the joints computed as forward dynamics.
Returns true in case of success, false otherwise.

The base acceleration should be provided by the user.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::KinDynWrapper::forwardDynamics(Eigen::Ref<const Eigen::VectorXd> motorTorqueAfterGearbox, Eigen::Ref<const Eigen::VectorXd> frictionTorques, Eigen::Ref<const Eigen::VectorXd> tauExt, Eigen::Ref<Eigen::VectorXd> nuDot)

forwardDynamics computes the forward dynamics.

Parameters
motorTorqueAfterGearbox joint motor torques.
frictionTorques joint friction torques.
tauExt torques generated by external contacts.
nuDot acceleration of the base plus acceleration of the joints computed as forward dynamics.
Returns true in case of success, false otherwise.

Eigen::Ref<const Eigen::VectorXd> BipedalLocomotion::Estimators::RobotDynamicsEstimator::KinDynWrapper::getNuDot()

getNuDot get the base and joint accelerations computed as forward dynamics.

Returns a Eigen::Vector of dimension 6 + nr_of_joints.