Class JointAdmittance

Inheritance Relationships

Base Type

Class Documentation

class JointAdmittance : public OpenSoT::tasks::velocity::Postural

The JointAdmittance class implements a simple admittance controller in velocity at the joints.

The implemented scheme is the following:

\( \boldsymbol{\Delta}\mathbf{q}_r = \mathbf{C}\boldsymbol{\Delta \tau} \)

where \( \mathbf{C} \in \mathbb{R}^{n \times n}\) is the Compliance matrix. The torque error is computed as:

\( \boldsymbol{\Delta \tau} = \mathbf{h} - \boldsymbol{\tau}_m \)

with \( \mathbf{h} \) containing the torques due to gravity and Coriolis/Centrifugal forces, computed from the robot feedback. The computed joint velocity reference is plugged in the postural task as a feed-forward desired joint velocity:

\( \boldsymbol{\Delta}\mathbf{q}_d = \boldsymbol{\Delta}\mathbf{q}_r + \lambda \left( \mathbf{q}_d - \mathbf{q}\right) \\ \)

Public Types

typedef std::shared_ptr<JointAdmittance> Ptr

Public Functions

JointAdmittance(XBot::ModelInterface &robot, XBot::ModelInterface &model)

JointAdmittance constructor.

Parameters
  • robot – is updated with the actual measurements from the robot (used to cpmuted the non-linear terms \( \mathbf{h} \))

  • model – is updated with the integrated state from the robot used to perform open-loop IK

void setJointCompliance(const Eigen::MatrixXd &C)

setJointCompliance set the Compliance matrix

Parameters

C – a SPD matrix

void setJointCompliance(const double C)

setJointCompliance set the same compiance to all the joints

Parameters

C – a positive or equal zero number

const Eigen::MatrixXd &getJointCompliance()

getJointCompliance

Returns

the actual Compliance matrix

void getJointCompliance(Eigen::MatrixXd &C)

getJointCompliance

Parameters

C – the actual Compliance matrix

void setFilterParams(const double time_step, const double damping, const double omega)

setFilterParams set all the parameters of the internal second order filter used to filter the \( \boldsymbol{\Delta \tau} \)

Parameters
  • time_step – of the filter

  • damping – of the filter

  • omega – of the filter

void setFilterTimeStep(const double time_step)

setFilterTimeStep

Parameters

time_step – of the filter

void setFilterDamping(const double damping)

setFilterDamping

Parameters

damping – of the filter

void setFilterOmega(const double omega)

setFilterOmega

Parameters

omega – rembember that: \( \omega = \frac{f}{2\pi} \) where \( f\) is the cut-off frequency.

Public Static Functions

static bool isJointAdmittance(OpenSoT::Task<Eigen::MatrixXd, Eigen::VectorXd>::TaskPtr task)

isJointAdmittance

Parameters

task – a generic task pointer

Returns

true if task is a JointAdmittance task

static OpenSoT::tasks::velocity::JointAdmittance::Ptr asJointAdmittance(OpenSoT::Task<Eigen::MatrixXd, Eigen::VectorXd>::TaskPtr task)

asJointAdmittance dynamic cast a generic task pointer to JointAdmittance task

Parameters

task – a generic task pointer

Returns

a pointer to a JointAdmittance task