41 #include <visp3/vs/vpServo.h> 46 #include <visp3/core/vpException.h> 49 #include <visp3/core/vpDebug.h> 70 : L(), error(), J1(), J1p(), s(), sStar(), e1(), e(), q_dot(), v(), servoType(
vpServo::NONE), rankJ1(0),
71 featureList(), desiredFeatureList(), featureSelectionList(), lambda(), signInteractionMatrix(1),
72 interactionMatrixType(DESIRED), inversionType(PSEUDO_INVERSE), cVe(), init_cVe(false), cVf(), init_cVf(false),
73 fVe(), init_fVe(false), eJe(), init_eJe(false), fJe(), init_fJe(false), errorComputed(false),
74 interactionMatrixComputed(false), dim_task(0), taskWasKilled(false), forceInteractionMatrixComputation(false),
75 WpW(), I_WpW(), P(), sv(), mu(4.), e1_initial(), iscJcIdentity(true), cJc(6, 6)
95 :
L(),
error(),
J1(),
J1p(),
s(),
sStar(),
e1(),
e(),
q_dot(),
v(),
servoType(servo_type),
rankJ1(0),
featureList(),
119 vpTRACE(
"--- Begin Warning Warning Warning Warning Warning ---");
120 vpTRACE(
"--- You should explicitly call vpServo.kill()... ---");
121 vpTRACE(
"--- End Warning Warning Warning Warning Warning ---");
291 if (dof.
size() == 6) {
293 for (
unsigned int i = 0; i < 6; i++) {
294 if (std::fabs(dof[i]) > std::numeric_limits<double>::epsilon()) {
315 switch (displayLevel) {
317 os <<
"Visual servoing task: " << std::endl;
319 os <<
"Type of control law " << std::endl;
322 os <<
"Type of task have not been chosen yet ! " << std::endl;
325 os <<
"Eye-in-hand configuration " << std::endl;
326 os <<
"Control in the camera frame " << std::endl;
329 os <<
"Eye-in-hand configuration " << std::endl;
330 os <<
"Control in the articular frame " << std::endl;
333 os <<
"Eye-to-hand configuration " << std::endl;
334 os <<
"s_dot = _L_cVe_eJe q_dot " << std::endl;
337 os <<
"Eye-to-hand configuration " << std::endl;
338 os <<
"s_dot = _L_cVe_fVe_eJe q_dot " << std::endl;
341 os <<
"Eye-to-hand configuration " << std::endl;
342 os <<
"s_dot = _L_cVf_fJe q_dot " << std::endl;
346 os <<
"List of visual features : s" << std::endl;
347 std::list<vpBasicFeature *>::const_iterator it_s;
348 std::list<vpBasicFeature *>::const_iterator it_s_star;
349 std::list<unsigned int>::const_iterator it_select;
352 ++it_s, ++it_select) {
354 (*it_s)->print((*it_select));
357 os <<
"List of desired visual features : s*" << std::endl;
361 (*it_s_star)->print((*it_select));
364 os <<
"Interaction Matrix Ls " << std::endl;
366 os <<
L << std::endl;
368 os <<
"not yet computed " << std::endl;
371 os <<
"Error vector (s-s*) " << std::endl;
373 os <<
error.
t() << std::endl;
375 os <<
"not yet computed " << std::endl;
378 os <<
"Gain : " <<
lambda << std::endl;
384 os <<
"Type of control law " << std::endl;
387 os <<
"Type of task have not been chosen yet ! " << std::endl;
390 os <<
"Eye-in-hand configuration " << std::endl;
391 os <<
"Control in the camera frame " << std::endl;
394 os <<
"Eye-in-hand configuration " << std::endl;
395 os <<
"Control in the articular frame " << std::endl;
398 os <<
"Eye-to-hand configuration " << std::endl;
399 os <<
"s_dot = _L_cVe_eJe q_dot " << std::endl;
402 os <<
"Eye-to-hand configuration " << std::endl;
403 os <<
"s_dot = _L_cVe_fVe_eJe q_dot " << std::endl;
406 os <<
"Eye-to-hand configuration " << std::endl;
407 os <<
"s_dot = _L_cVf_fJe q_dot " << std::endl;
414 os <<
"List of visual features : s" << std::endl;
416 std::list<vpBasicFeature *>::const_iterator it_s;
417 std::list<unsigned int>::const_iterator it_select;
420 ++it_s, ++it_select) {
422 (*it_s)->print((*it_select));
427 os <<
"List of desired visual features : s*" << std::endl;
429 std::list<vpBasicFeature *>::const_iterator it_s_star;
430 std::list<unsigned int>::const_iterator it_select;
435 (*it_s_star)->print((*it_select));
440 os <<
"Gain : " <<
lambda << std::endl;
444 os <<
"Interaction Matrix Ls " << std::endl;
446 os <<
L << std::endl;
448 os <<
"not yet computed " << std::endl;
457 os <<
"Error vector (s-s*) " << std::endl;
459 os <<
error.
t() << std::endl;
461 os <<
"not yet computed " << std::endl;
562 unsigned int dim = 0;
563 std::list<vpBasicFeature *>::const_iterator it_s;
564 std::list<unsigned int>::const_iterator it_select;
567 ++it_s, ++it_select) {
568 dim += (*it_s)->getDimension(*it_select);
581 static void computeInteractionMatrixFromList(
const std::list<vpBasicFeature *> &
featureList,
601 unsigned int rowL = L.
getRows();
602 const unsigned int colL = 6;
615 unsigned int cursorL = 0;
617 std::list<vpBasicFeature *>::const_iterator it;
618 std::list<unsigned int>::const_iterator it_select;
622 matrixTmp = (*it)->interaction(*it_select);
623 unsigned int rowMatrixTmp = matrixTmp.
getRows();
624 unsigned int colMatrixTmp = matrixTmp.
getCols();
627 while (rowMatrixTmp + cursorL > rowL) {
629 L.
resize(rowL, colL,
false);
634 for (
unsigned int k = 0; k < rowMatrixTmp; ++k, ++cursorL) {
635 for (
unsigned int j = 0; j < colMatrixTmp; ++j) {
636 L[cursorL][j] = matrixTmp[k][j];
641 L.
resize(cursorL, colL,
false);
768 unsigned int cursorS = 0;
769 unsigned int cursorSStar = 0;
770 unsigned int cursorError = 0;
773 std::list<vpBasicFeature *>::const_iterator it_s;
774 std::list<vpBasicFeature *>::const_iterator it_s_star;
775 std::list<unsigned int>::const_iterator it_select;
778 it_s !=
featureList.end(); ++it_s, ++it_s_star, ++it_select) {
780 desired_s = (*it_s_star);
781 unsigned int select = (*it_select);
784 vectTmp = current_s->
get_s(select);
785 unsigned int dimVectTmp = vectTmp.
getRows();
786 while (dimVectTmp + cursorS > dimS) {
791 for (
unsigned int k = 0; k < dimVectTmp; ++k) {
792 s[cursorS++] = vectTmp[k];
796 vectTmp = desired_s->
get_s(select);
797 dimVectTmp = vectTmp.
getRows();
798 while (dimVectTmp + cursorSStar > dimSStar) {
802 for (
unsigned int k = 0; k < dimVectTmp; ++k) {
803 sStar[cursorSStar++] = vectTmp[k];
807 vectTmp = current_s->
error(*desired_s, select);
808 dimVectTmp = vectTmp.
getRows();
809 while (dimVectTmp + cursorError > dimError) {
813 for (
unsigned int k = 0; k < dimVectTmp; ++k) {
814 error[cursorError++] = vectTmp[k];
937 static int iteration = 0;
943 if (iteration == 0) {
945 vpERROR_TRACE(
"All the matrices are not correctly initialized");
947 "All the matrices are not correctly" 991 J1 = L *
cJc * cVa * aJe;
1001 bool imageComputed =
false;
1006 imageComputed =
true;
1018 if (imageComputed !=
true) {
1024 WpW = imJ1t * imJ1t.
t();
1027 std::cout <<
"rank J1: " <<
rankJ1 << std::endl;
1028 imJ1t.
print(std::cout, 10,
"imJ1t");
1029 imJ1.
print(std::cout, 10,
"imJ1");
1032 J1.
print(std::cout, 10,
"J1");
1089 static int iteration = 0;
1096 if (iteration == 0) {
1098 vpERROR_TRACE(
"All the matrices are not correctly initialized");
1100 "All the matrices are not correctly" 1105 vpERROR_TRACE(
"All the matrices are not correctly updated");
1151 bool imageComputed =
false;
1156 imageComputed =
true;
1168 if (imageComputed !=
true) {
1174 WpW = imJ1t * imJ1t.
t();
1177 std::cout <<
"rank J1 " <<
rankJ1 << std::endl;
1178 std::cout <<
"imJ1t" << std::endl << imJ1t;
1179 std::cout <<
"imJ1" << std::endl << imJ1;
1181 std::cout <<
"WpW" << std::endl <<
WpW;
1182 std::cout <<
"J1" << std::endl <<
J1;
1183 std::cout <<
"J1p" << std::endl <<
J1p;
1190 if (iteration == 0 || std::fabs(t) < std::numeric_limits<double>::epsilon()) {
1250 static int iteration = 0;
1256 if (iteration == 0) {
1258 vpERROR_TRACE(
"All the matrices are not correctly initialized");
1260 "All the matrices are not correctly" 1265 vpERROR_TRACE(
"All the matrices are not correctly updated");
1311 bool imageComputed =
false;
1316 imageComputed =
true;
1328 if (imageComputed !=
true) {
1334 WpW = imJ1t * imJ1t.
t();
1337 std::cout <<
"rank J1 " <<
rankJ1 << std::endl;
1338 std::cout <<
"imJ1t" << std::endl << imJ1t;
1339 std::cout <<
"imJ1" << std::endl << imJ1;
1341 std::cout <<
"WpW" << std::endl <<
WpW;
1342 std::cout <<
"J1" << std::endl <<
J1;
1343 std::cout <<
"J1p" << std::endl <<
J1p;
1350 if (iteration == 0 || std::fabs(t) < std::numeric_limits<double>::epsilon()) {
1394 else if (e0_ <= norm_e && norm_e <= e1_)
1395 sig = 1.0 / (1.0 + exp(-12.0 * ((norm_e - e0_) / ((e1_ - e0_))) + 6.0));
1407 P_norm_e = I - (1.0 / pp) * J1t * ee_t *
J1;
1409 P = sig * P_norm_e + (1 - sig) *
I_WpW;
1489 if (!useLargeProjectionOperator) {
1491 vpERROR_TRACE(
"no degree of freedom is free, cannot use secondary task");
1503 sec =
I_WpW * de2dt;
1590 const bool &useLargeProjectionOperator)
1594 if (!useLargeProjectionOperator) {
1596 vpERROR_TRACE(
"no degree of freedom is free, cannot use secondary task");
1669 const double &rho,
const double &rho1,
1670 const double &lambda_tune)
const 1674 if (qmin.
size() != n || qmax.
size() != n) {
1675 std::stringstream msg;
1676 msg <<
"Dimension vector qmin (" << qmin.
size()
1677 <<
") or qmax () does not correspond to the number of jacobian " 1679 msg <<
"qmin size: " << qmin.
size() << std::endl;
1682 if (q.
size() != n || dq.
size() != n) {
1683 vpERROR_TRACE(
"Dimension vector q or dq does not correspont to the " 1684 "number of jacobian columns");
1686 "the number of jacobian columns"));
1689 double lambda_l = 0.0;
1702 for (
unsigned int i = 0; i < n; i++) {
1703 q_l0_min[i] = qmin[i] + rho * (qmax[i] - qmin[i]);
1704 q_l0_max[i] = qmax[i] - rho * (qmax[i] - qmin[i]);
1706 q_l1_min[i] = q_l0_min[i] - rho * rho1 * (qmax[i] - qmin[i]);
1707 q_l1_max[i] = q_l0_max[i] + rho * rho1 * (qmax[i] - qmin[i]);
1709 if (q[i] < q_l0_min[i])
1711 else if (q[i] > q_l0_max[i])
1717 for (
unsigned int i = 0; i < n; i++) {
1718 if (q[i] > q_l0_min[i] && q[i] < q_l0_max[i])
1729 if (q[i] < q_l1_min[i] || q[i] > q_l1_max[i])
1730 q2_i = -(1 + lambda_tune) * b * Pg_i;
1733 if (q[i] >= q_l0_max[i] && q[i] <= q_l1_max[i])
1734 lambda_l = 1 / (1 + exp(-12 * ((q[i] - q_l0_max[i]) / (q_l1_max[i] - q_l0_max[i])) + 6));
1736 else if (q[i] >= q_l1_min[i] && q[i] <= q_l0_min[i])
1737 lambda_l = 1 / (1 + exp(-12 * ((q[i] - q_l0_min[i]) / (q_l1_min[i] - q_l0_min[i])) + 6));
1739 q2_i = -lambda_l * (1 + lambda_tune) * b * Pg_i;
Implementation of a matrix and operations on matrices.
vpMatrix pseudoInverse(double svThreshold=1e-6) const
unsigned int getTaskRank() const
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
vpServoType servoType
Chosen visual servoing control law.
double frobeniusNorm() const
void setDeallocate(vpBasicFeatureDeallocatorType d)
bool interactionMatrixComputed
true if the interaction matrix has been computed.
bool taskWasKilled
Flag to indicate if the task was killed.
unsigned int rankJ1
Rank of the task Jacobian.
vpVelocityTwistMatrix cVf
Twist transformation matrix between Rf and Rc.
vpMatrix getTaskJacobianPseudoInverse() const
void addFeature(vpBasicFeature &s, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
vpVelocityTwistMatrix fVe
Twist transformation matrix between Re and Rf.
vpColVector sv
Singular values from the pseudo inverse.
vpColVector e1
Primary task .
void set_eJe(const vpMatrix &eJe_)
Error that can be emited by the vpServo class and its derivates.
unsigned int getRows() const
vpColVector secondaryTaskJointLimitAvoidance(const vpColVector &q, const vpColVector &dq, const vpColVector &jointMin, const vpColVector &jointMax, const double &rho=0.1, const double &rho1=0.3, const double &lambda_tune=0.7) const
vpMatrix fJe
Jacobian expressed in the robot reference frame.
unsigned int size() const
Return the number of elements of the 2D array.
vpColVector q_dot
Articular velocity.
vpColVector get_s(unsigned int select=FEATURE_ALL) const
Get the feature vector .
unsigned int dim_task
Dimension of the task updated during computeControlLaw().
vpServoInversionType inversionType
static Type abs(const Type &x)
vpColVector secondaryTask(const vpColVector &de2dt, const bool &useLargeProjectionOperator=false)
unsigned int getCols() const
class that defines what is a visual feature
virtual vpColVector error(const vpBasicFeature &s_star, unsigned int select=FEATURE_ALL)
vpMatrix computeInteractionMatrix()
std::list< unsigned int > featureSelectionList
vp_deprecated void setIdentity(const double &val=1.0)
bool iscJcIdentity
Boolean to know if cJc is identity (for fast computation)
bool testInitialization()
vpColVector computeError()
int signInteractionMatrix
vpColVector computeControlLaw()
unsigned int getDimension() const
Return the task dimension.
vpMatrix J1
Task Jacobian .
void setCameraDoF(const vpColVector &dof)
vpMatrix L
Interaction matrix.
bool forceInteractionMatrixComputation
Force the interaction matrix computation even if it is already done.
vpAdaptiveGain lambda
Gain used in the control law.
vpVelocityTwistMatrix cVe
Twist transformation matrix between Re and Rc.
int print(std::ostream &s, unsigned int length, const std::string &intro="") const
vpColVector getCol(unsigned int j) const
vpMatrix getLargeP() const
vpServoIteractionMatrixType
vpMatrix transpose() const
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
vpMatrix getI_WpW() const
void resize(unsigned int i, bool flagNullify=true)
void computeProjectionOperators()
vpMatrix getTaskJacobian() const
std::list< vpBasicFeature * > desiredFeatureList
List of desired visual features .
Implementation of column vector and the associated operations.
void set_cVe(const vpVelocityTwistMatrix &cVe_)
No degree of freedom is available to achieve the secondary task.
void print(const vpServo::vpServoPrintType display_level=ALL, std::ostream &os=std::cout)
vpMatrix I_WpW
Projection operators .
vpColVector v
Camera velocity.
virtual vpBasicFeature * duplicate() const =0
bool errorComputed
true if the error has been computed.
vpMatrix WpW
Projection operators .
vpMatrix J1p
Pseudo inverse of the task Jacobian.
std::list< vpBasicFeature * > featureList
List of current visual features .
void setServo(const vpServoType &servo_type)
void init()
Basic initialization.
vpServoIteractionMatrixType interactionMatrixType
Type of the interaction matrox (current, mean, desired, user)
vpMatrix eJe
Jacobian expressed in the end-effector frame.
Current or desired feature list is empty.