Class InverseDynamics

Class Documentation

class InverseDynamics

The InverseDynamics class is a utility to help the computation of wholebody inverse dynamics controllers with contacts.

Public Types

enum CONTACT_MODEL

Values:

enumerator POINT_CONTACT
enumerator SURFACE_CONTACT
typedef std::shared_ptr<InverseDynamics> Ptr

Public Functions

InverseDynamics(const std::vector<std::string> links_in_contact, XBot::ModelInterface &model, const CONTACT_MODEL &contact_model = CONTACT_MODEL::SURFACE_CONTACT)

InverseDynamics constructor.

Parameters
  • links_in_contact – a vector of string each one representing a contact

  • model

  • contact_model – the type of contact model defines the number of contact force variables, default is surface: 6dofs

const AffineHelper &getJointsAccelerationAffine() const

getJointsAccelerationAffine return the Affine related to the joint accelerations

Returns

_qddot

const std::vector<AffineHelper> &getContactsWrenchAffine() const

getContactsWrenchAffine return a vector of Affines each related to a contact wrench

Returns

_contacts_wrench

const std::shared_ptr<OpenSoT::OptvarHelper> getSerializer() const

getSerializer return a pointer to the object which contains all the variables of the Inverse Dynamics

Returns

bool computedTorque(const Eigen::VectorXd &x, Eigen::VectorXd &tau, Eigen::VectorXd &qddot, std::vector<Eigen::Vector6d> &contact_wrench)

computedTorque given the solution from the solver which contains all the optimization variables, returns the torque to send to the robot

Parameters
  • x – optimized variables

  • tau – computed torques

  • qddot – computed accelerations from solution x

  • contact_wrench – computed wrenches from solution x

Returns

true if the model is fixed base, false if the base wrench is not 0 (for floating base models)

void log(XBot::MatLogger2::Ptr &logger)

log internal variables: wrenches, tau and qddot

Parameters

logger