2.12 The Impedance class
The Impedance class deals with the impedance controller [16]. This class should
be use with the class Resolve_acc. Resolve_acc will make sure the end effector
follow the compliant trajectory generated by Impedance. The end effector
impedance is defined in terms of its translational and rotational part
[16].
Constructor
Syntax
Impedance();
Impedance(const Robot_basic & robot, const DiagonalMatrix & Mp,
const DiagonalMatrix & Dp, const DiagonalMatrix & Kp,
const Matrix & Km, const DiagonalMatrix & Mo,
const DiagonalMatrix & Do, const DiagonalMatrix & Ko);
Impedance(const Impedance & x);
Impedance & operator=(const Impedance & x);
Description
Impedance object constructor, copy constructor and equal operator.
Return Value
None
control
Syntax
short control(const ColumnVector & pdpp, const ColumnVector & pdp,
const ColumnVector & pd, const ColumnVector & wdp,
const ColumnVector & wd, const Quaternion & qd,
const ColumnVector & f, const ColumnVector & n,
const Real dt);
Description
This function generate the compliant trajectory for a desired trajectory.
Return Value
Status, as a short int.
- 0 successful
- WRONG_SIZE (regarding the input vector)
Mp, Dp, Kp, Mo, Do, Ko
Syntax
short set_Mp(const DiagonalMatrix & Mp);
short set_Mp(Real MP_i, const short i);
short set_Dp(const DiagonalMatrix & Dp);
short set_Dp(Real Dp_i, const short i);
short set_Kp(const DiagonalMatrix & Kp);
short set_Kp(Real Kp_i, const short i);
short set_Mo(const DiagonalMatrix & Mo);
short set_Mo(Real Mo_i, const short i);
short set_Do(const DiagonalMatrix & Do);
short set_Do(Real Do_i, const short i);
short set_Ko(const DiagonalMatrix & Ko);
short set_Ko(Real Ko_i, const short i);
Description
These functions sets the translational and rotational impedance parameters.
Return Value
Status, as a short int.
- 0 successful
- WRONG_SIZE (regarding the input vector)