iCub-main
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
iCub::iKin::MultiRefMinJerkCtrl Class Reference

A class derived from iKinCtrl implementing the multi-referential approach (pdf). More...

#include <iKinInv.h>

+ Inheritance diagram for iCub::iKin::MultiRefMinJerkCtrl:

Public Member Functions

 MultiRefMinJerkCtrl (iKinChain &c, unsigned int _ctrlPose, double _Ts, bool nonIdealPlant=false)
 Constructor. More...
 
virtual yarp::sig::Vector iterate (yarp::sig::Vector &xd, yarp::sig::Vector &qd, const unsigned int verbose=0)
 Executes one iteration of the control algorithm. More...
 
virtual yarp::sig::Vector iterate (yarp::sig::Vector &xd, yarp::sig::Vector &qd, yarp::sig::Vector &xdot_set, const unsigned int verbose=0)
 Executes one iteration of the control algorithm. More...
 
virtual void restart (const yarp::sig::Vector &q0)
 Reinitializes the algorithm's internal state and resets the starting point. More...
 
virtual std::string getAlgoName ()
 Returns the algorithm's name. More...
 
double get_guardRatio () const
 Returns the guard ratio for the joints span (0.1 by default). More...
 
double get_gamma () const
 Returns the parameter gamma which is used to blend the contribute of the task controller versus the contribute of the joint controller. More...
 
double get_execTime () const
 Returns the task execution time in seconds (1.0 by default). More...
 
yarp::sig::Vector get_qdot () const
 Returns the actual derivative of joint angles. More...
 
yarp::sig::Vector get_xdot () const
 Returns the actual derivative of End-Effector Pose (6 components; xdot=J*qdot). More...
 
void set_guardRatio (double _guardRatio)
 Sets the guard ratio (in [0 1]). More...
 
void set_gamma (double _gamma)
 Sets the parameter gamma which is used to blend the contribute of the task controller versus the contribute of the joint controller. More...
 
virtual void set_q (const yarp::sig::Vector &q0)
 Sets the joint angles values. More...
 
double set_execTime (const double _execTime, const bool warn=false)
 Sets the task execution time in seconds. More...
 
void add_compensation (const yarp::sig::Vector &comp)
 Adds to the controller input a further compensation term. More...
 
void setPlantParameters (const yarp::os::Property &parameters, const std::string &entryTag="dimension")
 Allows user to assign values to the parameters of plant under control (for the configuration space only). More...
 
virtual ~MultiRefMinJerkCtrl ()
 Destructor. More...
 
- Public Member Functions inherited from iCub::iKin::iKinCtrl
 iKinCtrl (iKinChain &c, unsigned int _ctrlPose)
 Constructor. More...
 
virtual void setChainConstraints (bool _constrained)
 Enables/Disables joint angles constraints. More...
 
void switchWatchDog (bool sw)
 Switch on/off the watchDog mechanism to trigger deadLocks. More...
 
virtual void setInTargetTol (double tol_x)
 Sets tolerance for in-target check (5e-3 by default). More...
 
virtual double getInTargetTol () const
 Returns tolerance for in-target check. More...
 
virtual void setWatchDogTol (double tol_q)
 Sets tolerance for watchDog check (1e-4 by default). More...
 
virtual double getWatchDogTol () const
 Returns tolerance for watchDog check. More...
 
virtual void setWatchDogMaxIter (int maxIter)
 Sets maximum number of iterations to trigger the watchDog (200 by default). More...
 
virtual int getWatchDogMaxIter () const
 Returns maximum number of iterations to trigger the watchDog. More...
 
virtual bool isInTarget ()
 Checks if the End-Effector is in target. More...
 
int get_state () const
 Returns the algorithm's state. More...
 
void set_ctrlPose (unsigned int _ctrlPose)
 Sets the state of Pose control settings. More...
 
unsigned int get_ctrlPose () const
 Returns the state of Pose control settings. More...
 
unsigned int get_dim () const
 Returns the number of Chain DOF. More...
 
unsigned int get_iter () const
 Returns the number of performed iterations. More...
 
virtual yarp::sig::Vector get_x () const
 Returns the actual cartesian position of the End-Effector. More...
 
virtual yarp::sig::Vector get_e () const
 Returns the actual cartesian position error. More...
 
virtual yarp::sig::Vector get_q () const
 Returns the actual joint angles values. More...
 
virtual yarp::sig::Vector get_grad () const
 Returns the actual gradient. More...
 
virtual yarp::sig::Matrix get_J () const
 Returns the actual Jacobian used in computation. More...
 
virtual double dist () const
 Returns the actual distance from the target in cartesian space (euclidean norm is used). More...
 
virtual ~iKinCtrl ()
 Default destructor. More...
 

Protected Member Functions

virtual void computeGuard ()
 
virtual void computeWeight ()
 
virtual yarp::sig::Vector iterate (yarp::sig::Vector &xd, yarp::sig::Vector &qd, yarp::sig::Vector *xdot_set, const unsigned int verbose)
 
virtual void inTargetFcn ()
 Method called whenever in target. More...
 
virtual void deadLockRecoveryFcn ()
 Method called whenever the watchDog is triggered. More...
 
virtual void printIter (const unsigned int verbose)
 Dumps warning or status messages. More...
 
virtual bool test_convergence (const double)
 Tests convergence by comparing the size of the algorithm internal structure (may be the gradient norm or the simplex size or whatever) to a certain tolerance. More...
 
virtual yarp::sig::Vector iterate (yarp::sig::Vector &, const unsigned int)
 Executes one iteration of the control algorithm. More...
 
virtual yarp::sig::Vector solve (yarp::sig::Vector &, const double, const int, const unsigned int, int *, bool *)
 Iterates the control algorithm trying to converge on the target. More...
 
- Protected Member Functions inherited from iCub::iKin::iKinCtrl
virtual yarp::sig::Vector calc_e ()
 Computes the error according to the current controller settings (complete pose/translational/rotational part). More...
 
virtual void update_state ()
 Updates the control state. More...
 
virtual void watchDog ()
 Handles the watchDog. More...
 
virtual yarp::sig::Vector checkVelocity (const yarp::sig::Vector &_qdot, double _Ts)
 Checks each joint velocity and sets it to zero if it steers the joint out of range. More...
 
unsigned int printHandling (const unsigned int verbose=0)
 Method to be called within the printIter routine inherited by children in order to handle the highest word of verbose integer. More...
 

Protected Attributes

ctrl::minJerkVelCtrlmjCtrlJoint
 
ctrl::minJerkVelCtrlmjCtrlTask
 
ctrl::IntegratorI
 
yarp::sig::Vector q_set
 
yarp::sig::Vector qdot
 
yarp::sig::Vector xdot
 
yarp::sig::Matrix W
 
yarp::sig::Matrix Eye6
 
double Ts
 
double execTime
 
double gamma
 
double guardRatio
 
yarp::sig::Vector qGuard
 
yarp::sig::Vector qGuardMinInt
 
yarp::sig::Vector qGuardMinExt
 
yarp::sig::Vector qGuardMinCOG
 
yarp::sig::Vector qGuardMaxInt
 
yarp::sig::Vector qGuardMaxExt
 
yarp::sig::Vector qGuardMaxCOG
 
yarp::sig::Vector compensation
 
- Protected Attributes inherited from iCub::iKin::iKinCtrl
iKinChainchain
 
unsigned int ctrlPose
 
yarp::sig::Vector x_set
 
yarp::sig::Vector x
 
yarp::sig::Vector e
 
yarp::sig::Vector q
 
yarp::sig::Matrix J
 
yarp::sig::Matrix Jt
 
yarp::sig::Matrix pinvJ
 
yarp::sig::Vector grad
 
yarp::sig::Vector q_old
 
double inTargetTol
 
double watchDogTol
 
unsigned int dim
 
unsigned int iter
 
int state
 
bool watchDogOn
 
int watchDogCnt
 
int watchDogMaxIter
 

Detailed Description

A class derived from iKinCtrl implementing the multi-referential approach (pdf).

Note
Minimum-Jerk controllers in Task Space and Joint Space

Definition at line 759 of file iKinInv.h.

Constructor & Destructor Documentation

◆ MultiRefMinJerkCtrl()

MultiRefMinJerkCtrl::MultiRefMinJerkCtrl ( iKinChain c,
unsigned int  _ctrlPose,
double  _Ts,
bool  nonIdealPlant = false 
)

Constructor.

Parameters
cis the Chain object on which the control operates. Do not change Chain DOF from this point onwards!!
_ctrlPoseone of the following: IKINCTRL_POSE_FULL => complete pose control. IKINCTRL_POSE_XYZ => translational part of pose controlled. IKINCTRL_POSE_ANG => rotational part of pose controlled.
_Tsis the nominal controller sample time.
nonIdealPlantif true allocate a dedicated min-jerk controller for the configuration space capable of compansating plants that differ from pure integrators.

Definition at line 725 of file iKinInv.cpp.

◆ ~MultiRefMinJerkCtrl()

MultiRefMinJerkCtrl::~MultiRefMinJerkCtrl ( )
virtual

Destructor.

Definition at line 984 of file iKinInv.cpp.

Member Function Documentation

◆ add_compensation()

void MultiRefMinJerkCtrl::add_compensation ( const yarp::sig::Vector &  comp)

Adds to the controller input a further compensation term.

Parameters
compthe compensation term.
Note
The compensation term holds for one iteration step, then it is automatically set to zero for safety reasons.

Definition at line 956 of file iKinInv.cpp.

◆ computeGuard()

void MultiRefMinJerkCtrl::computeGuard ( )
protectedvirtual

Definition at line 779 of file iKinInv.cpp.

◆ computeWeight()

void MultiRefMinJerkCtrl::computeWeight ( )
protectedvirtual

Definition at line 797 of file iKinInv.cpp.

◆ deadLockRecoveryFcn()

virtual void iCub::iKin::MultiRefMinJerkCtrl::deadLockRecoveryFcn ( )
inlineprotectedvirtual

Method called whenever the watchDog is triggered.

Put here the code to recover from deadLock. Shall be implemented.

Implements iCub::iKin::iKinCtrl.

Definition at line 797 of file iKinInv.h.

◆ get_execTime()

double iCub::iKin::MultiRefMinJerkCtrl::get_execTime ( ) const
inline

Returns the task execution time in seconds (1.0 by default).

Returns
task execution time.

Definition at line 907 of file iKinInv.h.

◆ get_gamma()

double iCub::iKin::MultiRefMinJerkCtrl::get_gamma ( ) const
inline

Returns the parameter gamma which is used to blend the contribute of the task controller versus the contribute of the joint controller.

Returns
gamma.

Definition at line 901 of file iKinInv.h.

◆ get_guardRatio()

double iCub::iKin::MultiRefMinJerkCtrl::get_guardRatio ( ) const
inline

Returns the guard ratio for the joints span (0.1 by default).

Note
The weights W_theta^-1 are non-zero only within the range [ q_min+0.5*guardRatio*D, q_max-0.5*guardRatio*D ] for each join, where D=q_max-q_min.
Returns
guard ratio.

Definition at line 893 of file iKinInv.h.

◆ get_qdot()

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::get_qdot ( ) const
inline

Returns the actual derivative of joint angles.

Returns
the actual derivative of joint angles.

Definition at line 913 of file iKinInv.h.

◆ get_xdot()

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::get_xdot ( ) const
inline

Returns the actual derivative of End-Effector Pose (6 components; xdot=J*qdot).

Returns
the actual derivative of End-Effector Pose.

Definition at line 920 of file iKinInv.h.

◆ getAlgoName()

virtual std::string iCub::iKin::MultiRefMinJerkCtrl::getAlgoName ( )
inlinevirtual

Returns the algorithm's name.

Returns
algorithm name as string. Shall be implemented.

Implements iCub::iKin::iKinCtrl.

Definition at line 884 of file iKinInv.h.

◆ inTargetFcn()

virtual void iCub::iKin::MultiRefMinJerkCtrl::inTargetFcn ( )
inlineprotectedvirtual

Method called whenever in target.

Shall be implemented.

Implements iCub::iKin::iKinCtrl.

Definition at line 796 of file iKinInv.h.

◆ iterate() [1/4]

virtual yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::iterate ( yarp::sig::Vector &  xd,
const unsigned int  verbose 
)
inlineprotectedvirtual

Executes one iteration of the control algorithm.

Parameters
xdis the End-Effector target Pose to be tracked.
verboseis a integer whose 32 bits are intended as follows. The lowest word (16 bits) progressively enables different levels of warning messages or status dump: the larger this value the more detailed is the output (0x####0000=>off by default). The highest word indicates how many successive calls to the dump shall be skipped in order to reduce the amount of information on the screen (ex: 0x0000####=>print all iterations, 0x0001####=>print one iteration and skip the next one, 0x0002####=> print one iteration and skip the next two).
Returns
current estimation of joints configuration. Shall be implemented.

Implements iCub::iKin::iKinCtrl.

Definition at line 802 of file iKinInv.h.

◆ iterate() [2/4]

virtual yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::iterate ( yarp::sig::Vector &  xd,
yarp::sig::Vector &  qd,
const unsigned int  verbose = 0 
)
virtual

Executes one iteration of the control algorithm.

Parameters
xdis the End-Effector target Pose to be tracked.
qdis the target joint angles (it shall satisfy the forward kinematic function xd=f(qd)).
verboseis a integer whose 32 bits are intended as follows. The lowest word (16 bits) progressively enables different levels of warning messages or status dump: the larger this value the more detailed is the output (0x####0000=>off by default). The highest word indicates how many successive calls to the dump shall be skipped in order to reduce the amount of information on the screen (ex: 0x0000####=>print all iterations, 0x0001####=>print one iteration and skip the next one, 0x0002####=> print one iteration and skip the next two).
Returns
current estimation of joints configuration.
Note
The reason why qd is provided externally instead of computed here is to discouple the inverse kinematic problem (which may require some computational effort depending on the current pose xd) from the reaching issue.

◆ iterate() [3/4]

virtual yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::iterate ( yarp::sig::Vector &  xd,
yarp::sig::Vector &  qd,
yarp::sig::Vector &  xdot_set,
const unsigned int  verbose = 0 
)
virtual

Executes one iteration of the control algorithm.

Parameters
xdis the End-Effector target Pose to be tracked.
qdis the target joint angles (it shall satisfy the forward kinematic function xd=f(qd)).
xdot_setis the Task Space reference velocity; the vector size is 7 (due to the axis-angle notation) and units are [rad/s].
verboseis a integer whose 32 bits are intended as follows. The lowest word (16 bits) progressively enables different levels of warning messages or status dump: the larger this value the more detailed is the output (0x####0000=>off by default). The highest word indicates how many successive calls to the dump shall be skipped in order to reduce the amount of information on the screen (ex: 0x0000####=>print all iterations, 0x0001####=>print one iteration and skip the next one, 0x0002####=> print one iteration and skip the next two).
Returns
current estimation of joints configuration.
Note
The reason why qd is provided externally instead of computed here is to discouple the inverse kinematic problem (which may require some computational effort depending on the current pose xd) from the reaching issue.

◆ iterate() [4/4]

virtual yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::iterate ( yarp::sig::Vector &  xd,
yarp::sig::Vector &  qd,
yarp::sig::Vector *  xdot_set,
const unsigned int  verbose 
)
protectedvirtual

◆ printIter()

void MultiRefMinJerkCtrl::printIter ( const unsigned int  verbose)
protectedvirtual

Dumps warning or status messages.

Parameters
verboseis a integer whose 32 bits are intended as follows. The lowest word (16 bits) progressively enables different levels of warning messages or status dump: the larger this value the more detailed is the output (0x####0000=>off by default). The highest word indicates how many successive calls to the dump shall be skipped in order to reduce the amount of information on the screen (ex: 0x0000####=>print all iterations, 0x0001####=>print one iteration and skip the next one, 0x0002####=> print one iteration and skip the next two).
Note
Angles are dumperd as degrees. Shall be implemented.

Implements iCub::iKin::iKinCtrl.

Definition at line 898 of file iKinInv.cpp.

◆ restart()

void MultiRefMinJerkCtrl::restart ( const yarp::sig::Vector &  q0)
virtual

Reinitializes the algorithm's internal state and resets the starting point.

Parameters
q0is the new starting point.

Reimplemented from iCub::iKin::iKinCtrl.

Definition at line 885 of file iKinInv.cpp.

◆ set_execTime()

double MultiRefMinJerkCtrl::set_execTime ( const double  _execTime,
const bool  warn = false 
)

Sets the task execution time in seconds.

Parameters
_execTime.
warnenable/disable warning message for thresholding (disabled by default).
Returns
the actual execTime.
Note
A lower bound equal to 10*Ts (Ts=controller's sample time) is imposed.

Definition at line 942 of file iKinInv.cpp.

◆ set_gamma()

void iCub::iKin::MultiRefMinJerkCtrl::set_gamma ( double  _gamma)
inline

Sets the parameter gamma which is used to blend the contribute of the task controller versus the contribute of the joint controller.

Parameters
_gamma.

Definition at line 934 of file iKinInv.h.

◆ set_guardRatio()

void MultiRefMinJerkCtrl::set_guardRatio ( double  _guardRatio)

Sets the guard ratio (in [0 1]).

Parameters
_guardRatio.

Definition at line 770 of file iKinInv.cpp.

◆ set_q()

void MultiRefMinJerkCtrl::set_q ( const yarp::sig::Vector &  q0)
virtual

Sets the joint angles values.

Parameters
q0is the joint angles vector.

Reimplemented from iCub::iKin::iKinCtrl.

Definition at line 934 of file iKinInv.cpp.

◆ setPlantParameters()

void MultiRefMinJerkCtrl::setPlantParameters ( const yarp::os::Property &  parameters,
const std::string &  entryTag = "dimension" 
)

Allows user to assign values to the parameters of plant under control (for the configuration space only).

In case the controlled plant is not a pure integrator, then it can be modelled as the following transfer function: (Kp/s)*((1+Tz*s)/(1+2*Zeta*Tw*s+(Tw*s)^2))

Parameters
parameterscontains the set of plant parameters for each dimension in form of a Property object.

Available parameters are:

dimension_# < list>: example (dimension_2 ((Kp 1.0) (Tw 0.1) ...)), specifies the Kp, Tz, Tw and Zeta parameters for a given dimension of the plant ("dimension_2" in the example). Dimensions are 0-based numbers.

Parameters
entryTagspecifies an entry tag different from "dimension".

Definition at line 965 of file iKinInv.cpp.

◆ solve()

virtual yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::solve ( yarp::sig::Vector &  xd,
const double  tol_size,
const int  max_iter,
const unsigned int  verbose,
int *  exit_code,
bool *  exhalt 
)
inlineprotectedvirtual

Iterates the control algorithm trying to converge on the target.

Parameters
xdis the End-Effector target Pose to be tracked.
tol_sizeexits if test_convergence(tol_size) is true (tol_size<0 disables this check, default).
max_iterexits if iter>=max_iter (max_iter<0 disables this check, default).
verboseis a integer whose 32 bits are intended as follows. The lowest word (16 bits) progressively enables different levels of warning messages or status dump: the larger this value the more detailed is the output (0x####0000=>off by default). The highest word indicates how many successive calls to the dump shall be skipped in order to reduce the amount of information on the screen (ex: 0x0000####=>print all iterations, 0x0001####=>print one iteration and skip the next one, 0x0002####=> print one iteration and skip the next two).
exit_codestores the exit code (NULL by default). Test for one of this: IKINCTRL_RET_TOLX IKINCTRL_RET_TOLSIZE IKINCTRL_RET_TOLQ IKINCTRL_RET_MAXITER IKINCTRL_RET_EXHALT
exhaltchecks for an external request to exit (NULL by default).
See also
setInTargetTol
getInTargetTol

Reimplemented from iCub::iKin::iKinCtrl.

Definition at line 803 of file iKinInv.h.

◆ test_convergence()

virtual bool iCub::iKin::MultiRefMinJerkCtrl::test_convergence ( const double  tol_size)
inlineprotectedvirtual

Tests convergence by comparing the size of the algorithm internal structure (may be the gradient norm or the simplex size or whatever) to a certain tolerance.

Parameters
tol_sizeis tolerance to compare to. Shall be implemented.

Implements iCub::iKin::iKinCtrl.

Definition at line 801 of file iKinInv.h.

Member Data Documentation

◆ compensation

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::compensation
protected

Definition at line 789 of file iKinInv.h.

◆ execTime

double iCub::iKin::MultiRefMinJerkCtrl::execTime
protected

Definition at line 781 of file iKinInv.h.

◆ Eye6

yarp::sig::Matrix iCub::iKin::MultiRefMinJerkCtrl::Eye6
protected

Definition at line 778 of file iKinInv.h.

◆ gamma

double iCub::iKin::MultiRefMinJerkCtrl::gamma
protected

Definition at line 782 of file iKinInv.h.

◆ guardRatio

double iCub::iKin::MultiRefMinJerkCtrl::guardRatio
protected

Definition at line 783 of file iKinInv.h.

◆ I

ctrl::Integrator* iCub::iKin::MultiRefMinJerkCtrl::I
protected

Definition at line 772 of file iKinInv.h.

◆ mjCtrlJoint

ctrl::minJerkVelCtrl* iCub::iKin::MultiRefMinJerkCtrl::mjCtrlJoint
protected

Definition at line 770 of file iKinInv.h.

◆ mjCtrlTask

ctrl::minJerkVelCtrl* iCub::iKin::MultiRefMinJerkCtrl::mjCtrlTask
protected

Definition at line 771 of file iKinInv.h.

◆ q_set

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::q_set
protected

Definition at line 774 of file iKinInv.h.

◆ qdot

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::qdot
protected

Definition at line 775 of file iKinInv.h.

◆ qGuard

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::qGuard
protected

Definition at line 785 of file iKinInv.h.

◆ qGuardMaxCOG

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::qGuardMaxCOG
protected

Definition at line 787 of file iKinInv.h.

◆ qGuardMaxExt

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::qGuardMaxExt
protected

Definition at line 787 of file iKinInv.h.

◆ qGuardMaxInt

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::qGuardMaxInt
protected

Definition at line 787 of file iKinInv.h.

◆ qGuardMinCOG

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::qGuardMinCOG
protected

Definition at line 786 of file iKinInv.h.

◆ qGuardMinExt

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::qGuardMinExt
protected

Definition at line 786 of file iKinInv.h.

◆ qGuardMinInt

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::qGuardMinInt
protected

Definition at line 786 of file iKinInv.h.

◆ Ts

double iCub::iKin::MultiRefMinJerkCtrl::Ts
protected

Definition at line 780 of file iKinInv.h.

◆ W

yarp::sig::Matrix iCub::iKin::MultiRefMinJerkCtrl::W
protected

Definition at line 777 of file iKinInv.h.

◆ xdot

yarp::sig::Vector iCub::iKin::MultiRefMinJerkCtrl::xdot
protected

Definition at line 776 of file iKinInv.h.


The documentation for this class was generated from the following files: