Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpServo.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
9 * See the file LICENSE.txt at the root directory of this source
10 * distribution for additional information about the GNU GPL.
11 *
12 * For using ViSP with software that can not be combined with the GNU
13 * GPL, please contact Inria about acquiring a ViSP Professional
14 * Edition License.
15 *
16 * See https://visp.inria.fr for more information.
17 *
18 * This software was developed at:
19 * Inria Rennes - Bretagne Atlantique
20 * Campus Universitaire de Beaulieu
21 * 35042 Rennes Cedex
22 * France
23 *
24 * If you have questions regarding the use of this file, please contact
25 * Inria at visp@inria.fr
26 *
27 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29 *
30 * Description:
31 * Visual servoing control law.
32 */
33
34
39
40#include <sstream>
41
42#include <visp3/core/vpException.h>
43#include <visp3/core/vpDebug.h>
44#include <visp3/vs/vpServo.h>
45
58
60 : L(), error(), J1(), J1p(), s(), sStar(), e1(), e(), q_dot(), v(), servoType(servo_type), rankJ1(0), featureList(),
62 inversionType(PSEUDO_INVERSE), cVe(), init_cVe(false), cVf(), init_cVf(false), fVe(), init_fVe(false), eJe(),
63 init_eJe(false), fJe(), init_fJe(false), errorComputed(false), interactionMatrixComputed(false), dim_task(0),
64 taskWasKilled(false), forceInteractionMatrixComputation(false), WpW(), I_WpW(), P(), sv(), mu(4), e1_initial(),
65 iscJcIdentity(true), cJc(6, 6), m_first_iteration(true)
66{
67 cJc.eye();
68}
69
71
73{
74 // type of visual servoing
76
77 // Twist transformation matrix
78 init_cVe = false;
79 init_cVf = false;
80 init_fVe = false;
81 // Jacobians
82 init_eJe = false;
83 init_fJe = false;
84
85 dim_task = 0;
86
87 featureList.clear();
88 desiredFeatureList.clear();
90
92
95
97 errorComputed = false;
98
99 taskWasKilled = false;
100
102
103 rankJ1 = 0;
104
105 m_first_iteration = true;
106}
107
109{
110 if (taskWasKilled == false) {
111 // kill the current and desired feature lists
112
113 // current list
114 for (std::list<vpBasicFeature *>::iterator it = featureList.begin(); it != featureList.end(); ++it) {
115 if ((*it)->getDeallocate() == vpBasicFeature::vpServo) {
116 delete (*it);
117 (*it) = nullptr;
118 }
119 }
120 // desired list
121 for (std::list<vpBasicFeature *>::iterator it = desiredFeatureList.begin(); it != desiredFeatureList.end(); ++it) {
122 if ((*it)->getDeallocate() == vpBasicFeature::vpServo) {
123 delete (*it);
124 (*it) = nullptr;
125 }
126 }
127
128 featureList.clear();
129 desiredFeatureList.clear();
130 taskWasKilled = true;
131 }
132}
133
134void vpServo::setServo(const vpServoType &servo_type)
135{
136 this->servoType = servo_type;
137
140 else
142
143 // when the control is directly compute in the camera frame
144 // we relieve the end-user to initialize cVa and aJe
147 set_cVe(_cVe);
148
149 vpMatrix _eJe;
150 _eJe.eye(6);
151 set_eJe(_eJe);
152 }
153}
154
156{
157 if (dof.size() == 6) {
158 iscJcIdentity = true;
159 for (unsigned int i = 0; i < 6; i++) {
160 if (std::fabs(dof[i]) > std::numeric_limits<double>::epsilon()) {
161 cJc[i][i] = 1.0;
162 }
163 else {
164 cJc[i][i] = 0.0;
165 iscJcIdentity = false;
166 }
167 }
168 }
169}
170
171void vpServo::print(const vpServo::vpServoPrintType displayLevel, std::ostream &os)
172{
173 switch (displayLevel) {
174 case vpServo::ALL: {
175 os << "Visual servoing task: " << std::endl;
176
177 os << "Type of control law " << std::endl;
178 switch (servoType) {
179 case NONE:
180 os << "Type of task have not been chosen yet ! " << std::endl;
181 break;
182 case EYEINHAND_CAMERA:
183 os << "Eye-in-hand configuration " << std::endl;
184 os << "Control in the camera frame " << std::endl;
185 break;
187 os << "Eye-in-hand configuration " << std::endl;
188 os << "Control in the articular frame " << std::endl;
189 break;
191 os << "Eye-to-hand configuration " << std::endl;
192 os << "s_dot = _L_cVe_eJe q_dot " << std::endl;
193 break;
195 os << "Eye-to-hand configuration " << std::endl;
196 os << "s_dot = _L_cVe_fVe_eJe q_dot " << std::endl;
197 break;
199 os << "Eye-to-hand configuration " << std::endl;
200 os << "s_dot = _L_cVf_fJe q_dot " << std::endl;
201 break;
202 }
203
204 os << "List of visual features : s" << std::endl;
205 std::list<vpBasicFeature *>::const_iterator it_s;
206 std::list<vpBasicFeature *>::const_iterator it_s_star;
207 std::list<unsigned int>::const_iterator it_select;
208
209 for (it_s = featureList.begin(), it_select = featureSelectionList.begin(); it_s != featureList.end();
210 ++it_s, ++it_select) {
211 os << "";
212 (*it_s)->print((*it_select));
213 }
214
215 os << "List of desired visual features : s*" << std::endl;
216 for (it_s_star = desiredFeatureList.begin(), it_select = featureSelectionList.begin();
217 it_s_star != desiredFeatureList.end(); ++it_s_star, ++it_select) {
218 os << "";
219 (*it_s_star)->print((*it_select));
220 }
221
222 os << "Interaction Matrix Ls " << std::endl;
224 os << L << std::endl;
225 }
226 else {
227 os << "not yet computed " << std::endl;
228 }
229
230 os << "Error vector (s-s*) " << std::endl;
231 if (errorComputed) {
232 os << error.t() << std::endl;
233 }
234 else {
235 os << "not yet computed " << std::endl;
236 }
237
238 os << "Gain : " << lambda << std::endl;
239
240 break;
241 }
242
243 case vpServo::CONTROLLER: {
244 os << "Type of control law " << std::endl;
245 switch (servoType) {
246 case NONE:
247 os << "Type of task have not been chosen yet ! " << std::endl;
248 break;
249 case EYEINHAND_CAMERA:
250 os << "Eye-in-hand configuration " << std::endl;
251 os << "Control in the camera frame " << std::endl;
252 break;
254 os << "Eye-in-hand configuration " << std::endl;
255 os << "Control in the articular frame " << std::endl;
256 break;
258 os << "Eye-to-hand configuration " << std::endl;
259 os << "s_dot = _L_cVe_eJe q_dot " << std::endl;
260 break;
262 os << "Eye-to-hand configuration " << std::endl;
263 os << "s_dot = _L_cVe_fVe_eJe q_dot " << std::endl;
264 break;
266 os << "Eye-to-hand configuration " << std::endl;
267 os << "s_dot = _L_cVf_fJe q_dot " << std::endl;
268 break;
269 }
270 break;
271 }
272
274 os << "List of visual features : s" << std::endl;
275
276 std::list<vpBasicFeature *>::const_iterator it_s;
277 std::list<unsigned int>::const_iterator it_select;
278
279 for (it_s = featureList.begin(), it_select = featureSelectionList.begin(); it_s != featureList.end();
280 ++it_s, ++it_select) {
281 os << "";
282 (*it_s)->print((*it_select));
283 }
284 break;
285 }
287 os << "List of desired visual features : s*" << std::endl;
288
289 std::list<vpBasicFeature *>::const_iterator it_s_star;
290 std::list<unsigned int>::const_iterator it_select;
291
292 for (it_s_star = desiredFeatureList.begin(), it_select = featureSelectionList.begin();
293 it_s_star != desiredFeatureList.end(); ++it_s_star, ++it_select) {
294 os << "";
295 (*it_s_star)->print((*it_select));
296 }
297 break;
298 }
299 case vpServo::GAIN: {
300 os << "Gain : " << lambda << std::endl;
301 break;
302 }
304 os << "Interaction Matrix Ls " << std::endl;
306 os << L << std::endl;
307 }
308 else {
309 os << "not yet computed " << std::endl;
310 }
311 break;
312 }
313
315 case vpServo::MINIMUM:
316
317 {
318 os << "Error vector (s-s*) " << std::endl;
319 if (errorComputed) {
320 os << error.t() << std::endl;
321 }
322 else {
323 os << "not yet computed " << std::endl;
324 }
325
326 break;
327 }
328 }
329}
330
331void vpServo::addFeature(vpBasicFeature &s_cur, vpBasicFeature &s_star, unsigned int select)
332{
333 featureList.push_back(&s_cur);
334 desiredFeatureList.push_back(&s_star);
335 featureSelectionList.push_back(select);
336}
337
338void vpServo::addFeature(vpBasicFeature &s_cur, unsigned int select)
339{
340 featureList.push_back(&s_cur);
341
342 // in fact we have a problem with s_star that is not defined
343 // by the end user.
344
345 // If the same user want to compute the interaction at the desired position
346 // this "virtual feature" must exist
347
348 // a solution is then to duplicate the current feature (s* = s)
349 // and reinitialized s* to 0
350
351 // it remains the deallocation issue therefore a flag that stipulates that
352 // the feature has been allocated in vpServo is set
353
354 // vpServo must deallocate the memory (see ~vpServo and kill() )
355
356 vpBasicFeature *s_star;
357 s_star = s_cur.duplicate();
358
359 s_star->init();
361
362 desiredFeatureList.push_back(s_star);
363 featureSelectionList.push_back(select);
364}
365
366unsigned int vpServo::getDimension() const
367{
368 unsigned int dim = 0;
369 std::list<vpBasicFeature *>::const_iterator it_s;
370 std::list<unsigned int>::const_iterator it_select;
371
372 for (it_s = featureList.begin(), it_select = featureSelectionList.begin(); it_s != featureList.end();
373 ++it_s, ++it_select) {
374 dim += (*it_s)->getDimension(*it_select);
375 }
376
377 return dim;
378}
379
381 const vpServoInversionType &interactionMatrixInversion)
382{
383 this->interactionMatrixType = interactionMatrix_type;
384 this->inversionType = interactionMatrixInversion;
385}
386
387static void computeInteractionMatrixFromList(const std::list<vpBasicFeature *> &featureList,
388 const std::list<unsigned int> &featureSelectionList, vpMatrix &L)
389{
390 if (featureList.empty()) {
391 vpERROR_TRACE("feature list empty, cannot compute Ls");
392 throw(vpServoException(vpServoException::noFeatureError, "feature list empty, cannot compute Ls"));
393 }
394
395 /* The matrix dimension is not known before the affectation loop.
396 * It thus should be allocated on the flight, in the loop.
397 * The first assumption is that the size has not changed. A double
398 * reallocation (realloc(dim*2)) is done if necessary. In particular,
399 * [log_2(dim)+1] reallocations are done for the first matrix computation.
400 * If the allocated size is too large, a correction is done after the loop.
401 * The algorithmic cost is linear in affectation, logarithmic in allocation
402 * numbers and linear in allocation size.
403 */
404
405 /* First assumption: matrix dimensions have not changed. If 0, they are
406 * initialized to dim 1.*/
407 unsigned int rowL = L.getRows();
408 const unsigned int colL = 6;
409 if (0 == rowL) {
410 rowL = 1;
411 L.resize(rowL, colL);
412 }
413
414 /* vectTmp is used to store the return values of functions get_s() and
415 * error(). */
416 vpMatrix matrixTmp;
417
418 /* The cursor are the number of the next case of the vector array to
419 * be affected. A memory reallocation should be done when cursor
420 * is out of the vector-array range.*/
421 unsigned int cursorL = 0;
422
423 std::list<vpBasicFeature *>::const_iterator it;
424 std::list<unsigned int>::const_iterator it_select;
425
426 for (it = featureList.begin(), it_select = featureSelectionList.begin(); it != featureList.end(); ++it, ++it_select) {
427 /* Get s. */
428 matrixTmp = (*it)->interaction(*it_select);
429 unsigned int rowMatrixTmp = matrixTmp.getRows();
430 unsigned int colMatrixTmp = matrixTmp.getCols();
431
432 /* Check the matrix L size, and realloc if needed. */
433 while (rowMatrixTmp + cursorL > rowL) {
434 rowL *= 2;
435 L.resize(rowL, colL, false);
436 vpDEBUG_TRACE(15, "Realloc!");
437 }
438
439 /* Copy the temporarily matrix into L. */
440 for (unsigned int k = 0; k < rowMatrixTmp; ++k, ++cursorL) {
441 for (unsigned int j = 0; j < colMatrixTmp; ++j) {
442 L[cursorL][j] = matrixTmp[k][j];
443 }
444 }
445 }
446
447 L.resize(cursorL, colL, false);
448
449 return;
450}
451
453{
454 try {
455
456 switch (interactionMatrixType) {
457 case CURRENT: {
458 try {
459 computeInteractionMatrixFromList(this->featureList, this->featureSelectionList, L);
460 dim_task = L.getRows();
462 }
463
464 catch (...) {
465 throw;
466 }
467 } break;
468 case DESIRED: {
469 try {
471 computeInteractionMatrixFromList(this->desiredFeatureList, this->featureSelectionList, L);
472
473 dim_task = L.getRows();
475 }
476
477 }
478 catch (...) {
479 throw;
480 }
481 } break;
482 case MEAN: {
483 vpMatrix Lstar(L.getRows(), L.getCols());
484 try {
485 computeInteractionMatrixFromList(this->featureList, this->featureSelectionList, L);
486 computeInteractionMatrixFromList(this->desiredFeatureList, this->featureSelectionList, Lstar);
487 }
488 catch (...) {
489 throw;
490 }
491 L = (L + Lstar) / 2;
492
493 dim_task = L.getRows();
495 } break;
496 case USER_DEFINED:
497 // dim_task = L.getRows() ;
499 break;
500 }
501
502 }
503 catch (...) {
504 throw;
505 }
506 return L;
507}
508
510{
511 if (featureList.empty()) {
512 vpERROR_TRACE("feature list empty, cannot compute Ls");
513 throw(vpServoException(vpServoException::noFeatureError, "feature list empty, cannot compute Ls"));
514 }
515 if (desiredFeatureList.empty()) {
516 vpERROR_TRACE("feature list empty, cannot compute Ls");
517 throw(vpServoException(vpServoException::noFeatureError, "feature list empty, cannot compute Ls"));
518 }
519
520 try {
521 vpBasicFeature *current_s;
522 vpBasicFeature *desired_s;
523
524 /* The vector dimensions are not known before the affectation loop.
525 * They thus should be allocated on the flight, in the loop.
526 * The first assumption is that the size has not changed. A double
527 * reallocation (realloc(dim*2)) is done if necessary. In particular,
528 * [log_2(dim)+1] reallocations are done for the first error computation.
529 * If the allocated size is too large, a correction is done after the
530 * loop. The algorithmic cost is linear in affectation, logarithmic in
531 * allocation numbers and linear in allocation size. No assumptions are
532 * made concerning size of each vector: they are not said equal, and could
533 * be different.
534 */
535
536 /* First assumption: vector dimensions have not changed. If 0, they are
537 * initialized to dim 1.*/
538 unsigned int dimError = error.getRows();
539 unsigned int dimS = s.getRows();
540 unsigned int dimSStar = sStar.getRows();
541 if (0 == dimError) {
542 dimError = 1;
543 error.resize(dimError);
544 }
545 if (0 == dimS) {
546 dimS = 1;
547 s.resize(dimS);
548 }
549 if (0 == dimSStar) {
550 dimSStar = 1;
551 sStar.resize(dimSStar);
552 }
553
554 /* vectTmp is used to store the return values of functions get_s() and
555 * error(). */
556 vpColVector vectTmp;
557
558 /* The cursor are the number of the next case of the vector array to
559 * be affected. A memory reallocation should be done when cursor
560 * is out of the vector-array range.*/
561 unsigned int cursorS = 0;
562 unsigned int cursorSStar = 0;
563 unsigned int cursorError = 0;
564
565 /* For each cell of the list, copy value of s, s_star and error. */
566 std::list<vpBasicFeature *>::const_iterator it_s;
567 std::list<vpBasicFeature *>::const_iterator it_s_star;
568 std::list<unsigned int>::const_iterator it_select;
569
570 for (it_s = featureList.begin(), it_s_star = desiredFeatureList.begin(), it_select = featureSelectionList.begin();
571 it_s != featureList.end(); ++it_s, ++it_s_star, ++it_select) {
572 current_s = (*it_s);
573 desired_s = (*it_s_star);
574 unsigned int select = (*it_select);
575
576 /* Get s, and store it in the s vector. */
577 vectTmp = current_s->get_s(select);
578 unsigned int dimVectTmp = vectTmp.getRows();
579 while (dimVectTmp + cursorS > dimS) {
580 dimS *= 2;
581 s.resize(dimS, false);
582 vpDEBUG_TRACE(15, "Realloc!");
583 }
584 for (unsigned int k = 0; k < dimVectTmp; ++k) {
585 s[cursorS++] = vectTmp[k];
586 }
587
588 /* Get s_star, and store it in the s vector. */
589 vectTmp = desired_s->get_s(select);
590 dimVectTmp = vectTmp.getRows();
591 while (dimVectTmp + cursorSStar > dimSStar) {
592 dimSStar *= 2;
593 sStar.resize(dimSStar, false);
594 }
595 for (unsigned int k = 0; k < dimVectTmp; ++k) {
596 sStar[cursorSStar++] = vectTmp[k];
597 }
598
599 /* Get error, and store it in the s vector. */
600 vectTmp = current_s->error(*desired_s, select);
601 dimVectTmp = vectTmp.getRows();
602 while (dimVectTmp + cursorError > dimError) {
603 dimError *= 2;
604 error.resize(dimError, false);
605 }
606 for (unsigned int k = 0; k < dimVectTmp; ++k) {
607 error[cursorError++] = vectTmp[k];
608 }
609 }
610
611 /* If too much memory has been allocated, realloc. */
612 s.resize(cursorS, false);
613 sStar.resize(cursorSStar, false);
614 error.resize(cursorError, false);
615
616 /* Final modifications. */
617 dim_task = error.getRows();
618 errorComputed = true;
619 }
620 catch (...) {
621 throw;
622 }
623 return error;
624}
625
627{
628 switch (servoType) {
629 case NONE:
630 vpERROR_TRACE("No control law have been yet defined");
631 throw(vpServoException(vpServoException::servoError, "No control law have been yet defined"));
632 break;
633 case EYEINHAND_CAMERA:
634 return true;
635 break;
638 if (!init_cVe)
639 vpERROR_TRACE("cVe not initialized");
640 if (!init_eJe)
641 vpERROR_TRACE("eJe not initialized");
642 return (init_cVe && init_eJe);
643 break;
645 if (!init_cVf)
646 vpERROR_TRACE("cVf not initialized");
647 if (!init_fVe)
648 vpERROR_TRACE("fVe not initialized");
649 if (!init_eJe)
650 vpERROR_TRACE("eJe not initialized");
651 return (init_cVf && init_fVe && init_eJe);
652 break;
653
655 if (!init_cVf)
656 vpERROR_TRACE("cVf not initialized");
657 if (!init_fJe)
658 vpERROR_TRACE("fJe not initialized");
659 return (init_cVf && init_fJe);
660 }
661
662 return false;
663}
664
666{
667 switch (servoType) {
668 case NONE:
669 vpERROR_TRACE("No control law have been yet defined");
670 throw(vpServoException(vpServoException::servoError, "No control law have been yet defined"));
671 break;
672 case EYEINHAND_CAMERA:
673 return true;
675 if (!init_eJe)
676 vpERROR_TRACE("eJe not updated");
677 return (init_eJe);
679 if (!init_cVe)
680 vpERROR_TRACE("cVe not updated");
681 if (!init_eJe)
682 vpERROR_TRACE("eJe not updated");
683 return (init_cVe && init_eJe);
685 if (!init_fVe)
686 vpERROR_TRACE("fVe not updated");
687 if (!init_eJe)
688 vpERROR_TRACE("eJe not updated");
689 return (init_fVe && init_eJe);
691 if (!init_fJe)
692 vpERROR_TRACE("fJe not updated");
693 return (init_fJe);
694 }
695
696 return false;
697}
698
700{
701 vpVelocityTwistMatrix cVa; // Twist transformation matrix
702 vpMatrix aJe; // Jacobian
703
704 if (m_first_iteration) {
705 if (testInitialization() == false) {
706 vpERROR_TRACE("All the matrices are not correctly initialized");
707 throw(vpServoException(vpServoException::servoError, "Cannot compute control law. "
708 "All the matrices are not correctly"
709 "initialized."));
710 }
711 }
712 if (testUpdated() == false) {
713 vpERROR_TRACE("All the matrices are not correctly updated");
714 }
715
716 // test if all the required initialization have been done
717 switch (servoType) {
718 case NONE:
719 vpERROR_TRACE("No control law have been yet defined");
720 throw(vpServoException(vpServoException::servoError, "No control law have been yet defined"));
721 case EYEINHAND_CAMERA:
724
725 cVa = cVe;
726 aJe = eJe;
727
728 init_cVe = false;
729 init_eJe = false;
730 break;
732 cVa = cVf * fVe;
733 aJe = eJe;
734 init_fVe = false;
735 init_eJe = false;
736 break;
738 cVa = cVf;
739 aJe = fJe;
740 init_fJe = false;
741 break;
742 }
743
745 computeError();
746
747 // compute task Jacobian
748 if (iscJcIdentity)
749 J1 = L * cVa * aJe;
750 else
751 J1 = L * cJc * cVa * aJe;
752
753 // handle the eye-in-hand eye-to-hand case
755
756 // pseudo inverse of the task Jacobian
757 // and rank of the task Jacobian
758 // the image of J1 is also computed to allows the computation
759 // of the projection operator
760 vpMatrix imJ1t, imJ1;
761 bool imageComputed = false;
762
764 rankJ1 = J1.pseudoInverse(J1p, sv, m_pseudo_inverse_threshold, imJ1, imJ1t);
765
766 imageComputed = true;
767 }
768 else
769 J1p = J1.t();
770
771 if (rankJ1 == J1.getCols()) {
772 /* if no degrees of freedom remains (rank J1 = ndof)
773 WpW = I, multiply by WpW is useless
774 */
775 e1 = J1p * error; // primary task
776
777 WpW.eye(J1.getCols(), J1.getCols());
778 }
779 else {
780 if (imageComputed != true) {
781 vpMatrix Jtmp;
782 // image of J1 is computed to allows the computation
783 // of the projection operator
784 rankJ1 = J1.pseudoInverse(Jtmp, sv, m_pseudo_inverse_threshold, imJ1, imJ1t);
785 }
786 WpW = imJ1t.AAt();
787
788#ifdef DEBUG
789 std::cout << "rank J1: " << rankJ1 << std::endl;
790 imJ1t.print(std::cout, 10, "imJ1t");
791 imJ1.print(std::cout, 10, "imJ1");
792
793 WpW.print(std::cout, 10, "WpW");
794 J1.print(std::cout, 10, "J1");
795 J1p.print(std::cout, 10, "J1p");
796#endif
797 e1 = WpW * J1p * error;
798 }
799 e = -lambda(e1) * e1;
800
801 I.eye(J1.getCols());
802
803 // Compute classical projection operator
804 I_WpW = (I - WpW);
805
806 m_first_iteration = false;
807 return e;
808}
809
811{
812 vpVelocityTwistMatrix cVa; // Twist transformation matrix
813 vpMatrix aJe; // Jacobian
814
815 if (m_first_iteration) {
816 if (testInitialization() == false) {
817 vpERROR_TRACE("All the matrices are not correctly initialized");
818 throw(vpServoException(vpServoException::servoError, "Cannot compute control law "
819 "All the matrices are not correctly"
820 "initialized"));
821 }
822 }
823 if (testUpdated() == false) {
824 vpERROR_TRACE("All the matrices are not correctly updated");
825 }
826
827 // test if all the required initialization have been done
828 switch (servoType) {
829 case NONE:
830 vpERROR_TRACE("No control law have been yet defined");
831 throw(vpServoException(vpServoException::servoError, "No control law have been yet defined"));
832 break;
833 case EYEINHAND_CAMERA:
836
837 cVa = cVe;
838 aJe = eJe;
839
840 init_cVe = false;
841 init_eJe = false;
842 break;
844 cVa = cVf * fVe;
845 aJe = eJe;
846 init_fVe = false;
847 init_eJe = false;
848 break;
850 cVa = cVf;
851 aJe = fJe;
852 init_fJe = false;
853 break;
854 }
855
857 computeError();
858
859 // compute task Jacobian
860 J1 = L * cVa * aJe;
861
862 // handle the eye-in-hand eye-to-hand case
864
865 // pseudo inverse of the task Jacobian
866 // and rank of the task Jacobian
867 // the image of J1 is also computed to allows the computation
868 // of the projection operator
869 vpMatrix imJ1t, imJ1;
870 bool imageComputed = false;
871
873 rankJ1 = J1.pseudoInverse(J1p, sv, m_pseudo_inverse_threshold, imJ1, imJ1t);
874
875 imageComputed = true;
876 }
877 else
878 J1p = J1.t();
879
880 if (rankJ1 == J1.getCols()) {
881 /* if no degrees of freedom remains (rank J1 = ndof)
882 WpW = I, multiply by WpW is useless
883 */
884 e1 = J1p * error; // primary task
885
886 WpW.eye(J1.getCols());
887 }
888 else {
889 if (imageComputed != true) {
890 vpMatrix Jtmp;
891 // image of J1 is computed to allows the computation
892 // of the projection operator
893 rankJ1 = J1.pseudoInverse(Jtmp, sv, m_pseudo_inverse_threshold, imJ1, imJ1t);
894 }
895 WpW = imJ1t.AAt();
896
897#ifdef DEBUG
898 std::cout << "rank J1 " << rankJ1 << std::endl;
899 std::cout << "imJ1t" << std::endl << imJ1t;
900 std::cout << "imJ1" << std::endl << imJ1;
901
902 std::cout << "WpW" << std::endl << WpW;
903 std::cout << "J1" << std::endl << J1;
904 std::cout << "J1p" << std::endl << J1p;
905#endif
906 e1 = WpW * J1p * error;
907 }
908
909 // memorize the initial e1 value if the function is called the first time
910 // or if the time given as parameter is equal to 0.
911 if (m_first_iteration || std::fabs(t) < std::numeric_limits<double>::epsilon()) {
912 e1_initial = e1;
913 }
914 // Security check. If size of e1_initial and e1 differ, that means that
915 // e1_initial was not set
916 if (e1_initial.getRows() != e1.getRows())
917 e1_initial = e1;
918
919 e = -lambda(e1) * e1 + lambda(e1) * e1_initial * exp(-mu * t);
920
921 I.eye(J1.getCols());
922
923 // Compute classical projection operator
924 I_WpW = (I - WpW);
925
926 m_first_iteration = false;
927 return e;
928}
929
931{
932 vpVelocityTwistMatrix cVa; // Twist transformation matrix
933 vpMatrix aJe; // Jacobian
934
935 if (m_first_iteration) {
936 if (testInitialization() == false) {
937 vpERROR_TRACE("All the matrices are not correctly initialized");
938 throw(vpServoException(vpServoException::servoError, "Cannot compute control law "
939 "All the matrices are not correctly"
940 "initialized"));
941 }
942 }
943 if (testUpdated() == false) {
944 vpERROR_TRACE("All the matrices are not correctly updated");
945 }
946
947 // test if all the required initialization have been done
948 switch (servoType) {
949 case NONE:
950 vpERROR_TRACE("No control law have been yet defined");
951 throw(vpServoException(vpServoException::servoError, "No control law have been yet defined"));
952 case EYEINHAND_CAMERA:
955
956 cVa = cVe;
957 aJe = eJe;
958
959 init_cVe = false;
960 init_eJe = false;
961 break;
963 cVa = cVf * fVe;
964 aJe = eJe;
965 init_fVe = false;
966 init_eJe = false;
967 break;
969 cVa = cVf;
970 aJe = fJe;
971 init_fJe = false;
972 break;
973 }
974
976 computeError();
977
978 // compute task Jacobian
979 J1 = L * cVa * aJe;
980
981 // handle the eye-in-hand eye-to-hand case
983
984 // pseudo inverse of the task Jacobian
985 // and rank of the task Jacobian
986 // the image of J1 is also computed to allows the computation
987 // of the projection operator
988 vpMatrix imJ1t, imJ1;
989 bool imageComputed = false;
990
992 rankJ1 = J1.pseudoInverse(J1p, sv, m_pseudo_inverse_threshold, imJ1, imJ1t);
993
994 imageComputed = true;
995 }
996 else
997 J1p = J1.t();
998
999 if (rankJ1 == J1.getCols()) {
1000 /* if no degrees of freedom remains (rank J1 = ndof)
1001 WpW = I, multiply by WpW is useless
1002 */
1003 e1 = J1p * error; // primary task
1004
1005 WpW.eye(J1.getCols());
1006 }
1007 else {
1008 if (imageComputed != true) {
1009 vpMatrix Jtmp;
1010 // image of J1 is computed to allows the computation
1011 // of the projection operator
1012 rankJ1 = J1.pseudoInverse(Jtmp, sv, m_pseudo_inverse_threshold, imJ1, imJ1t);
1013 }
1014 WpW = imJ1t.AAt();
1015
1016#ifdef DEBUG
1017 std::cout << "rank J1 " << rankJ1 << std::endl;
1018 std::cout << "imJ1t" << std::endl << imJ1t;
1019 std::cout << "imJ1" << std::endl << imJ1;
1020
1021 std::cout << "WpW" << std::endl << WpW;
1022 std::cout << "J1" << std::endl << J1;
1023 std::cout << "J1p" << std::endl << J1p;
1024#endif
1025 e1 = WpW * J1p * error;
1026 }
1027
1028 // memorize the initial e1 value if the function is called the first time
1029 // or if the time given as parameter is equal to 0.
1030 if (m_first_iteration || std::fabs(t) < std::numeric_limits<double>::epsilon()) {
1031 e1_initial = e1;
1032 }
1033 // Security check. If size of e1_initial and e1 differ, that means that
1034 // e1_initial was not set
1035 if (e1_initial.getRows() != e1.getRows())
1036 e1_initial = e1;
1037
1038 e = -lambda(e1) * e1 + (e_dot_init + lambda(e1) * e1_initial) * exp(-mu * t);
1039
1040 I.eye(J1.getCols());
1041
1042 // Compute classical projection operator
1043 I_WpW = (I - WpW);
1044
1045 m_first_iteration = false;
1046 return e;
1047}
1048
1049void vpServo::computeProjectionOperators(const vpMatrix &J1_, const vpMatrix &I_, const vpMatrix &I_WpW_,
1050 const vpColVector &error_, vpMatrix &P_) const
1051{
1052 // Initialization
1053 unsigned int n = J1_.getCols();
1054 P_.resize(n, n);
1055
1056 // Compute gain depending by the task error to ensure a smooth change
1057 // between the operators.
1058 double e0_ = 0.1;
1059 double e1_ = 0.7;
1060 double sig = 0.0;
1061
1062 double norm_e = error_.frobeniusNorm();
1063 if (norm_e > e1_)
1064 sig = 1.0;
1065 else if (e0_ <= norm_e && norm_e <= e1_)
1066 sig = 1.0 / (1.0 + exp(-12.0 * ((norm_e - e0_) / ((e1_ - e0_))) + 6.0));
1067 else
1068 sig = 0.0;
1069
1070 vpMatrix eT_J = static_cast<vpMatrix>(error_.t()) * J1_;
1071 vpMatrix eT_J_JT_e = eT_J.AAt();
1072 double pp = eT_J_JT_e[0][0];
1073
1074 vpMatrix P_norm_e = I_ - (1.0 / pp) * eT_J.AtA();
1075
1076 P_ = sig * P_norm_e + (1 - sig) * I_WpW_;
1077
1078 return;
1079}
1080
1081vpColVector vpServo::secondaryTask(const vpColVector &de2dt, const bool &useLargeProjectionOperator)
1082{
1083 vpColVector sec;
1084
1085 if (!useLargeProjectionOperator) {
1086 if (rankJ1 == J1.getCols()) {
1087 vpERROR_TRACE("no degree of freedom is free, cannot use secondary task");
1088 throw(vpServoException(vpServoException::noDofFree, "no degree of freedom is free, cannot use secondary task"));
1089 }
1090 else {
1091#if 0
1092 // computed in computeControlLaw()
1093 vpMatrix I;
1094
1095 I.resize(J1.getCols(), J1.getCols());
1096 I.setIdentity();
1097 I_WpW = (I - WpW);
1098#endif
1099 // std::cout << "I-WpW" << std::endl << I_WpW <<std::endl ;
1100 sec = I_WpW * de2dt;
1101 }
1102 }
1103
1104 else {
1106
1107 sec = P * de2dt;
1108 }
1109
1110 return sec;
1111}
1112
1114 const bool &useLargeProjectionOperator)
1115{
1116 vpColVector sec;
1117
1118 if (!useLargeProjectionOperator) {
1119 if (rankJ1 == J1.getCols()) {
1120 vpERROR_TRACE("no degree of freedom is free, cannot use secondary task");
1121 throw(vpServoException(vpServoException::noDofFree, "no degree of freedom is free, cannot use secondary task"));
1122 }
1123 else {
1124
1125#if 0
1126 // computed in computeControlLaw()
1127 vpMatrix I;
1128
1129 I.resize(J1.getCols(), J1.getCols());
1130 I.setIdentity();
1131
1132 I_WpW = (I - WpW);
1133#endif
1134
1135 // To be coherent with the primary task the gain must be the same
1136 // between primary and secondary task.
1137 sec = -lambda(e1) * I_WpW * e2 + I_WpW * de2dt;
1138 }
1139 }
1140 else {
1142
1143 sec = -lambda(e1) * P * e2 + P * de2dt;
1144 }
1145
1146 return sec;
1147}
1148
1150 const vpColVector &qmin, const vpColVector &qmax,
1151 const double &rho, const double &rho1, const double &lambda_tune)
1152{
1153 unsigned int const n = J1.getCols();
1154
1155 if (qmin.size() != n || qmax.size() != n) {
1156 std::stringstream msg;
1157 msg << "Dimension vector qmin (" << qmin.size()
1158 << ") or qmax () does not correspond to the number of jacobian "
1159 "columns";
1160 msg << "qmin size: " << qmin.size() << std::endl;
1162 }
1163 if (q.size() != n || dq.size() != n) {
1164 vpERROR_TRACE("Dimension vector q or dq does not correspont to the "
1165 "number of jacobian columns");
1166 throw(vpServoException(vpServoException::dimensionError, "Dimension vector q or dq does not correspont to "
1167 "the number of jacobian columns"));
1168 }
1169
1170 double lambda_l = 0.0;
1171
1172 vpColVector q2(n);
1173
1174 vpColVector q_l0_min(n);
1175 vpColVector q_l0_max(n);
1176 vpColVector q_l1_min(n);
1177 vpColVector q_l1_max(n);
1178
1179 // Computation of gi ([nx1] vector) and lambda_l ([nx1] vector)
1180 vpMatrix g(n, n);
1181 vpColVector q2_i(n);
1182
1184
1185 for (unsigned int i = 0; i < n; i++) {
1186 q_l0_min[i] = qmin[i] + rho * (qmax[i] - qmin[i]);
1187 q_l0_max[i] = qmax[i] - rho * (qmax[i] - qmin[i]);
1188
1189 q_l1_min[i] = q_l0_min[i] - rho * rho1 * (qmax[i] - qmin[i]);
1190 q_l1_max[i] = q_l0_max[i] + rho * rho1 * (qmax[i] - qmin[i]);
1191
1192 if (q[i] < q_l0_min[i])
1193 g[i][i] = -1;
1194 else if (q[i] > q_l0_max[i])
1195 g[i][i] = 1;
1196 else
1197 g[i][i] = 0;
1198 }
1199
1200 for (unsigned int i = 0; i < n; i++) {
1201 if (q[i] > q_l0_min[i] && q[i] < q_l0_max[i])
1202 q2_i = 0 * q2_i;
1203
1204 else {
1205 vpColVector Pg_i(n);
1206 Pg_i = (P * g.getCol(i));
1207 double b = (vpMath::abs(dq[i])) / (vpMath::abs(Pg_i[i]));
1208
1209 if (b < 1.) // If the ratio b is big we don't activate the joint
1210 // avoidance limit for the joint.
1211 {
1212 if (q[i] < q_l1_min[i] || q[i] > q_l1_max[i])
1213 q2_i = -(1 + lambda_tune) * b * Pg_i;
1214
1215 else {
1216 if (q[i] >= q_l0_max[i] && q[i] <= q_l1_max[i])
1217 lambda_l = 1 / (1 + exp(-12 * ((q[i] - q_l0_max[i]) / (q_l1_max[i] - q_l0_max[i])) + 6));
1218
1219 else if (q[i] >= q_l1_min[i] && q[i] <= q_l0_min[i])
1220 lambda_l = 1 / (1 + exp(-12 * ((q[i] - q_l0_min[i]) / (q_l1_min[i] - q_l0_min[i])) + 6));
1221
1222 q2_i = -lambda_l * (1 + lambda_tune) * b * Pg_i;
1223 }
1224 }
1225 }
1226 q2 = q2 + q2_i;
1227 }
1228 return q2;
1229}
1230END_VISP_NAMESPACE
unsigned int getCols() const
Definition vpArray2D.h:423
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
Definition vpArray2D.h:448
unsigned int size() const
Return the number of elements of the 2D array.
Definition vpArray2D.h:435
unsigned int getRows() const
Definition vpArray2D.h:433
class that defines what is a visual feature
virtual vpColVector error(const vpBasicFeature &s_star, unsigned int select=FEATURE_ALL)
virtual void init()=0
void setDeallocate(vpBasicFeatureDeallocatorType d)
vpColVector get_s(unsigned int select=FEATURE_ALL) const
Get the feature vector .
virtual vpBasicFeature * duplicate() const =0
Implementation of column vector and the associated operations.
vpRowVector t() const
double frobeniusNorm() const
@ dimensionError
Bad dimension.
Definition vpException.h:71
static Type abs(const Type &x)
Definition vpMath.h:272
Implementation of a matrix and operations on matrices.
Definition vpMatrix.h:175
int print(std::ostream &s, unsigned int length, const std::string &intro="") const
Definition vpMatrix.cpp:836
vpMatrix AtA() const
vpColVector getCol(unsigned int j) const
Definition vpMatrix.cpp:560
vpMatrix AAt() const
Error that can be emitted by the vpServo class and its derivatives.
@ servoError
Other exception.
@ noDofFree
No degree of freedom is available to achieve the secondary task.
@ noFeatureError
Current or desired feature list is empty.
vpColVector q_dot
Articular velocity.
Definition vpServo.h:1210
unsigned int rankJ1
Rank of the task Jacobian.
Definition vpServo.h:1218
vpMatrix eJe
Jacobian expressed in the end-effector frame (e).
Definition vpServo.h:1282
int signInteractionMatrix
Definition vpServo.h:1233
vpMatrix WpW
Projection operators .
Definition vpServo.h:1315
vpVelocityTwistMatrix cVf
Twist transformation matrix between camera frame (c) and robot base frame (f).
Definition vpServo.h:1258
vpMatrix J1
Task Jacobian .
Definition vpServo.h:1191
bool testUpdated()
Definition vpServo.cpp:665
void setCameraDoF(const vpColVector &dof)
Definition vpServo.cpp:155
bool init_cVe
Definition vpServo.h:1256
bool errorComputed
true if the error has been computed.
Definition vpServo.h:1302
vpMatrix fJe
Jacobian expressed in the robot base frame (f).
Definition vpServo.h:1290
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition vpServo.cpp:380
vpServoType
Definition vpServo.h:166
@ EYETOHAND_L_cVe_eJe
Definition vpServo.h:190
@ EYEINHAND_CAMERA
Definition vpServo.h:176
@ EYETOHAND_L_cVf_fJe
Definition vpServo.h:204
@ EYEINHAND_L_cVe_eJe
Definition vpServo.h:183
@ EYETOHAND_L_cVf_fVe_eJe
Definition vpServo.h:197
unsigned int getDimension() const
Definition vpServo.cpp:366
bool init_cVf
Definition vpServo.h:1264
double mu
Definition vpServo.h:1344
vpVelocityTwistMatrix cVe
Definition vpServo.h:1249
bool init_fJe
Definition vpServo.h:1295
void addFeature(vpBasicFeature &s_cur, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition vpServo.cpp:331
vpMatrix P
Definition vpServo.h:1334
void set_cVe(const vpVelocityTwistMatrix &cVe_)
Definition vpServo.h:1058
vpColVector e1
Primary task .
Definition vpServo.h:1205
vpColVector e1_initial
Definition vpServo.h:1351
bool forceInteractionMatrixComputation
Force the interaction matrix computation even if it is already done.
Definition vpServo.h:1310
vpColVector secondaryTaskJointLimitAvoidance(const vpColVector &q, const vpColVector &dq, const vpColVector &qmin, const vpColVector &qmax, const double &rho=0.1, const double &rho1=0.3, const double &lambda_tune=0.7)
Definition vpServo.cpp:1149
void print(const vpServo::vpServoPrintType display_level=ALL, std::ostream &os=std::cout)
Definition vpServo.cpp:171
void kill()
Definition vpServo.cpp:108
vpMatrix cJc
Definition vpServo.h:1360
vpVelocityTwistMatrix fVe
Definition vpServo.h:1269
void set_eJe(const vpMatrix &eJe_)
Definition vpServo.h:1121
vpColVector secondaryTask(const vpColVector &de2dt, const bool &useLargeProjectionOperator=false)
Definition vpServo.cpp:1081
bool taskWasKilled
Flag to indicate if the task was killed.
Definition vpServo.h:1308
bool testInitialization()
Definition vpServo.cpp:626
void setServo(const vpServoType &servo_type)
Definition vpServo.cpp:134
std::list< vpBasicFeature * > featureList
List of current visual features .
Definition vpServo.h:1221
vpColVector error
Definition vpServo.h:1189
bool iscJcIdentity
Boolean to know if cJc is identity (for fast computation).
Definition vpServo.h:1354
vpMatrix I_WpW
Projection operators .
Definition vpServo.h:1317
vpColVector v
Camera velocity.
Definition vpServo.h:1212
virtual ~vpServo()
Definition vpServo.cpp:70
vpColVector sStar
Definition vpServo.h:1202
vpMatrix computeInteractionMatrix()
Definition vpServo.cpp:452
vpMatrix J1p
Pseudo inverse of the task Jacobian.
Definition vpServo.h:1193
vpColVector s
Definition vpServo.h:1198
vpMatrix I
Identity matrix.
Definition vpServo.h:1313
void computeProjectionOperators(const vpMatrix &J1_, const vpMatrix &I_, const vpMatrix &I_WpW_, const vpColVector &error_, vpMatrix &P_) const
Definition vpServo.cpp:1049
std::list< vpBasicFeature * > desiredFeatureList
List of desired visual features .
Definition vpServo.h:1223
vpServo()
Definition vpServo.cpp:47
bool m_first_iteration
True until first call of computeControlLaw() is achieved.
Definition vpServo.h:1362
vpMatrix L
Interaction matrix.
Definition vpServo.h:1184
vpServoType servoType
Chosen visual servoing control law.
Definition vpServo.h:1215
vpServoIteractionMatrixType interactionMatrixType
Type of the interaction matrix (current, mean, desired, user).
Definition vpServo.h:1235
double m_pseudo_inverse_threshold
Threshold used in the pseudo inverse.
Definition vpServo.h:1364
void init()
Definition vpServo.cpp:72
vpServoInversionType
Definition vpServo.h:241
@ PSEUDO_INVERSE
Definition vpServo.h:250
std::list< unsigned int > featureSelectionList
Definition vpServo.h:1226
vpColVector computeControlLaw()
Definition vpServo.cpp:699
vpColVector e
Task .
Definition vpServo.h:1207
bool init_eJe
Definition vpServo.h:1287
vpServoPrintType
Definition vpServo.h:257
@ ALL
Print all the task information.
Definition vpServo.h:258
@ CONTROLLER
Print the type of controller law.
Definition vpServo.h:259
@ ERROR_VECTOR
Print the error vector .
Definition vpServo.h:260
@ GAIN
Print the gain .
Definition vpServo.h:263
@ FEATURE_CURRENT
Print the current features .
Definition vpServo.h:261
@ FEATURE_DESIRED
Print the desired features .
Definition vpServo.h:262
@ MINIMUM
Same as vpServo::vpServoPrintType::ERROR_VECTOR.
Definition vpServo.h:265
@ INTERACTION_MATRIX
Print the interaction matrix.
Definition vpServo.h:264
vpServo(const vpServo &)=delete
vpColVector sv
Singular values from the pseudo inverse.
Definition vpServo.h:1337
vpServoIteractionMatrixType
Definition vpServo.h:211
@ DESIRED
Definition vpServo.h:223
@ USER_DEFINED
Definition vpServo.h:234
@ CURRENT
Definition vpServo.h:217
bool interactionMatrixComputed
true if the interaction matrix has been computed.
Definition vpServo.h:1304
bool init_fVe
Definition vpServo.h:1275
vpColVector computeError()
Definition vpServo.cpp:509
unsigned int dim_task
Dimension of the task updated during computeControlLaw().
Definition vpServo.h:1306
vpServoInversionType inversionType
Definition vpServo.h:1238
vpAdaptiveGain lambda
Gain used in the control law.
Definition vpServo.h:1229
#define vpDEBUG_TRACE
Definition vpDebug.h:526
#define vpERROR_TRACE
Definition vpDebug.h:423