Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
vpViper.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2017 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
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 http://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  * Interface for a generic ADEPT Viper (either 650 or 850) robot.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
48 #include <visp3/core/vpDebug.h>
49 #include <visp3/core/vpVelocityTwistMatrix.h>
50 #include <visp3/robot/vpRobotException.h>
51 #include <visp3/core/vpCameraParameters.h>
52 #include <visp3/core/vpRxyzVector.h>
53 #include <visp3/core/vpTranslationVector.h>
54 #include <visp3/core/vpRotationMatrix.h>
55 #include <visp3/robot/vpViper.h>
56 #include <cmath> // std::fabs
57 #include <limits> // numeric_limits
58 
59 const unsigned int vpViper::njoint = 6;
60 
67  : eMc(), etc(), erc(), a1(0), d1(0), a2(), a3(), d4(0), d6(0), d7(0), c56(0), joint_max(), joint_min()
68 {
69  // Default values are initialized
70 
71  // Denavit Hartenberg parameters
72  a1 = 0.075;
73  a2 = 0.365;
74  a3 = 0.090;
75  d1 = 0.335;
76  d4 = 0.405;
77  d6 = 0.080;
78  d7 = 0.0666;
79  c56 = -341.33 / 9102.22;
80 
81  // Software joint limits in radians
83  joint_min[0] = vpMath::rad(-170);
84  joint_min[1] = vpMath::rad(-190);
85  joint_min[2] = vpMath::rad(-29);
86  joint_min[3] = vpMath::rad(-190);
87  joint_min[4] = vpMath::rad(-120);
88  joint_min[5] = vpMath::rad(-360);
90  joint_max[0] = vpMath::rad(170);
91  joint_max[1] = vpMath::rad(45);
92  joint_max[2] = vpMath::rad(256);
93  joint_max[3] = vpMath::rad(190);
94  joint_max[4] = vpMath::rad(120);
95  joint_max[5] = vpMath::rad(360);
96 
97  // End effector to camera transformation
98  eMc.eye();
99 }
100 
101 
102 
103 
127 {
129  fMc = get_fMc(q);
130 
131  return fMc;
132 }
133 
148 bool
149 vpViper::convertJointPositionInLimits(unsigned int joint, const double &q, double &q_mod, const bool &verbose) const
150 {
151  double eps = 0.01;
152  if (q >= joint_min[joint]-eps && q <= joint_max[joint]+eps ) {
153  q_mod = q;
154  return true;
155  }
156 
157  q_mod = q + 2*M_PI;
158  if (q_mod >= joint_min[joint]-eps && q_mod <= joint_max[joint]+eps ) {
159  return true;
160  }
161 
162  q_mod = q - 2*M_PI;
163  if (q_mod >= joint_min[joint]-eps && q_mod <= joint_max[joint]+eps ) {
164  return true;
165  }
166 
167  if (verbose) {
168  std::cout << "Joint " << joint << " not in limits: "
169  << this->joint_min[joint] << " < " << q << " < " << this->joint_max[joint] << std::endl;
170 
171  }
172 
173  return false;
174 }
175 
228 unsigned int
229 vpViper::getInverseKinematicsWrist(const vpHomogeneousMatrix & fMw, vpColVector & q, const bool &verbose) const
230 {
231  vpColVector q_sol[8];
232 
233  for (unsigned int i=0; i<8; i++)
234  q_sol[i].resize(6);
235 
236  double c1[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
237  double s1[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
238  double c3[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
239  double s3[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
240  double c23[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
241  double s23[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
242  double c4[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
243  double s4[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
244  double c5[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
245  double s5[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
246  double c6[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
247  double s6[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
248 
249  bool ok[8];
250 
251  if (q.getRows() != njoint)
252  q.resize(6);
253 
254  for (unsigned int i=0; i< 8; i++)
255  ok[i] = true;
256 
257  double px = fMw[0][3]; // a*c1
258  double py = fMw[1][3]; // a*s1
259  double pz = fMw[2][3];
260 
261  // Compute q1
262  double a_2 = px*px+py*py;
263  //if (a_2 == 0) {// singularity
264  if (std::fabs(a_2) <= std::numeric_limits<double>::epsilon()) {// singularity
265  c1[0] = cos(q[0]);
266  s1[0] = sin(q[0]);
267  c1[4] = cos(q[0]+M_PI);
268  s1[4] = sin(q[0]+M_PI);
269  }
270  else {
271  double a = sqrt(a_2);
272  c1[0] = px/a;
273  s1[0] = py/a;
274  c1[4] = -px/a;
275  s1[4] = -py/a;
276  }
277 
278  double q1_mod;
279  for(unsigned int i=0;i<8;i+=4) {
280  q_sol[i][0] = atan2(s1[i],c1[i]);
281  if (convertJointPositionInLimits(0, q_sol[i][0], q1_mod, verbose) == true) {
282  q_sol[i][0] = q1_mod;
283  for(unsigned int j=1;j<4;j++) {
284  c1[i+j] = c1[i];
285  s1[i+j] = s1[i];
286  q_sol[i+j][0] = q_sol[i][0];
287  }
288  }
289  else {
290  for(unsigned int j=1;j<4;j++)
291  ok[i+j] = false;
292  }
293  }
294 
295  // Compute q3
296  double K, q3_mod;
297  for(unsigned int i=0; i<8; i+=4) {
298  if(ok[i] == true) {
299  K = (px*px+py*py+pz*pz+a1*a1-a2*a2-a3*a3+d1*d1-d4*d4
300  - 2*(a1*c1[i]*px + a1*s1[i]*py + d1*pz)) / (2*a2);
301  double d4_a3_K = d4*d4+a3*a3-K*K;
302 
303  q_sol[i][2] = atan2(a3, d4) + atan2(K, sqrt(d4_a3_K));
304  q_sol[i+2][2] = atan2(a3, d4) + atan2(K, -sqrt(d4_a3_K));
305 
306  for (unsigned int j=0; j<4; j+=2) {
307  if (d4_a3_K < 0) {
308  for(unsigned int k=0; k<2; k++)
309  ok[i+j+k] = false;
310  }
311  else {
312  if (convertJointPositionInLimits(2, q_sol[i+j][2], q3_mod, verbose) == true) {
313  for(unsigned int k=0; k<2; k++) {
314  q_sol[i+j+k][2] = q3_mod;
315  c3[i+j+k] = cos(q3_mod);
316  s3[i+j+k] = sin(q3_mod);
317  }
318  }
319  else {
320  for(unsigned int k=0; k<2; k++)
321  ok[i+j+k] = false;
322  }
323  }
324  }
325  }
326  }
327  // std::cout << "ok apres q3: ";
328  // for (unsigned int i=0; i< 8; i++)
329  // std::cout << ok[i] << " ";
330  // std::cout << std::endl;
331 
332  // Compute q2
333  double q23[8], q2_mod;
334  for (unsigned int i=0; i<8; i+=2) {
335  if (ok[i] == true) {
336  // Compute q23 = q2+q3
337  c23[i] = (-(a3-a2*c3[i])*(c1[i]*px+s1[i]*py-a1)-(d1-pz)*(d4+a2*s3[i]))
338  / ( (c1[i]*px+s1[i]*py-a1)*(c1[i]*px+s1[i]*py-a1) +(d1-pz)*(d1-pz) );
339  s23[i] = ((d4+a2*s3[i])*(c1[i]*px+s1[i]*py-a1)-(d1-pz)*(a3-a2*c3[i]))
340  / ( (c1[i]*px+s1[i]*py-a1)*(c1[i]*px+s1[i]*py-a1) +(d1-pz)*(d1-pz) );
341  q23[i] = atan2(s23[i],c23[i]);
342  //std::cout << i << " c23 = " << c23[i] << " s23 = " << s23[i] << std::endl;
343  // q2 = q23 - q3
344  q_sol[i][1] = q23[i] - q_sol[i][2];
345 
346  if (convertJointPositionInLimits(1, q_sol[i][1], q2_mod, verbose) == true) {
347  for(unsigned int j=0; j<2; j++) {
348  q_sol[i+j][1] = q2_mod;
349  c23[i+j] = c23[i];
350  s23[i+j] = s23[i];
351  }
352  }
353  else {
354  for(unsigned int j=0; j<2; j++)
355  ok[i+j] = false;
356  }
357  }
358  }
359  // std::cout << "ok apres q2: ";
360  // for (unsigned int i=0; i< 8; i++)
361  // std::cout << ok[i] << " ";
362  // std::cout << std::endl;
363 
364  // Compute q4 as long as s5 != 0
365  double r13 = fMw[0][2];
366  double r23 = fMw[1][2];
367  double r33 = fMw[2][2];
368  double s4s5, c4s5, q4_mod, q5_mod;
369  for (unsigned int i=0; i<8; i+=2) {
370  if (ok[i] == true) {
371  s4s5 = -s1[i]*r13+c1[i]*r23;
372  c4s5 = c1[i]*c23[i]*r13+s1[i]*c23[i]*r23-s23[i]*r33;
373  if (fabs(s4s5) < vpMath::rad(0.5) && fabs(c4s5) < vpMath::rad(0.5)) {
374  // s5 = 0
375  c5[i] = c1[i]*s23[i]*r13+s1[i]*s23[i]*r23+c23[i]*r33;
376  //std::cout << "Singularity: s5 near 0: ";
377  if (c5[i] > 0.)
378  q_sol[i][4] = 0.0;
379  else
380  q_sol[i][4] = M_PI;
381 
382  if (convertJointPositionInLimits(4, q_sol[i][4], q5_mod, verbose) == true) {
383  for(unsigned int j=0; j<2; j++) {
384  q_sol[i+j][3] = q[3]; // keep current q4
385  q_sol[i+j][4] = q5_mod;
386  c4[i] = cos(q_sol[i+j][3]);
387  s4[i] = sin(q_sol[i+j][3]);
388  }
389  }
390  else {
391  for(unsigned int j=0; j<2; j++)
392  ok[i+j] = false;
393  }
394  }
395  else {
396  // s5 != 0
397 #if 0 // Modified 2016/03/10 since if and else are the same
398  //if (c4s5 == 0) {
399  if (std::fabs(c4s5) <= std::numeric_limits<double>::epsilon()) {
400  // c4 = 0
401  // vpTRACE("c4 = 0");
402  // q_sol[i][3] = q[3]; // keep current position
403  q_sol[i][3] = atan2(s4s5, c4s5);
404  }
405  else {
406  q_sol[i][3] = atan2(s4s5, c4s5);
407  }
408 #else
409  q_sol[i][3] = atan2(s4s5, c4s5);
410 #endif
411  if (convertJointPositionInLimits(3, q_sol[i][3], q4_mod, verbose) == true) {
412  q_sol[i][3] = q4_mod;
413  c4[i] = cos(q4_mod);
414  s4[i] = sin(q4_mod);
415  }
416  else {
417  ok[i] = false;
418  }
419  if (q_sol[i][3] > 0.)
420  q_sol[i+1][3] = q_sol[i][3] + M_PI;
421  else
422  q_sol[i+1][3] = q_sol[i][3] - M_PI;
423  if (convertJointPositionInLimits(3, q_sol[i+1][3], q4_mod, verbose) == true) {
424  q_sol[i+1][3] = q4_mod;
425  c4[i+1] = cos(q4_mod);
426  s4[i+1] = sin(q4_mod);
427  }
428  else {
429  ok[i+1] = false;
430  }
431 
432  // Compute q5
433  for (unsigned int j=0; j<2; j++) {
434  if (ok[i+j] == true) {
435  c5[i+j] = c1[i+j]*s23[i+j]*r13+s1[i+j]*s23[i+j]*r23+c23[i+j]*r33;
436  s5[i+j] = (c1[i+j]*c23[i+j]*c4[i+j]-s1[i+j]*s4[i+j])*r13
437  +(s1[i+j]*c23[i+j]*c4[i+j]+c1[i+j]*s4[i+j])*r23-s23[i+j]*c4[i+j]*r33;
438 
439  q_sol[i+j][4] = atan2(s5[i+j], c5[i+j]);
440  if (convertJointPositionInLimits(4, q_sol[i+j][4], q5_mod, verbose) == true) {
441  q_sol[i+j][4] = q5_mod;
442  }
443  else {
444 
445  ok[i+j] = false;
446  }
447  }
448  }
449  }
450  }
451  }
452 
453  // Compute q6
454  // 4 solutions for q6 and 4 more solutions by flipping the wrist (see below)
455  double r12 = fMw[0][1];
456  double r22 = fMw[1][1];
457  double r32 = fMw[2][1];
458  double q6_mod;
459  for (unsigned int i=0; i<8; i++) {
460  c6[i] = -(c1[i]*c23[i]*s4[i]+s1[i]*c4[i])*r12
461  +(c1[i]*c4[i]-s1[i]*c23[i]*s4[i])*r22+s23[i]*s4[i]*r32;
462  s6[i] = -(c1[i]*c23[i]*c4[i]*c5[i]-c1[i]*s23[i]*s5[i]
463  -s1[i]*s4[i]*c5[i])*r12
464  -(s1[i]*c23[i]*c4[i]*c5[i]-s1[i]*s23[i]*s5[i]+c1[i]*s4[i]*c5[i])*r22
465  +(c23[i]*s5[i]+s23[i]*c4[i]*c5[i])*r32;
466 
467  q_sol[i][5] = atan2(s6[i], c6[i]);
468  if (convertJointPositionInLimits(5, q_sol[i][5], q6_mod, verbose) == true) {
469  q_sol[i][5] = q6_mod;
470  }
471  else {
472  ok[i] = false;
473  }
474  }
475 
476  // Select the best config in terms of distance from the current position
477  unsigned int nbsol = 0;
478  unsigned int sol = 0;
479  vpColVector dist(8);
480  for (unsigned int i=0; i<8; i++) {
481  if (ok[i] == true) {
482  nbsol ++;
483  sol = i;
484  // dist[i] = vpColVector::distance(q, q_sol[i]);
485  vpColVector weight(6);
486  weight = 1;
487  weight[0] = 8;
488  weight[1] = weight[2] = 4;
489  dist[i] = 0;
490  for (unsigned int j=0; j< 6; j++) {
491  double rought_dist = q[j]- q_sol[i][j];
492  double modulo_dist = rought_dist;
493  if (rought_dist > 0) {
494  if (fabs(rought_dist - 2*M_PI) < fabs(rought_dist))
495  modulo_dist = rought_dist - 2*M_PI;
496  }
497  else {
498  if (fabs(rought_dist + 2*M_PI) < fabs(rought_dist))
499  modulo_dist = rought_dist + 2*M_PI;
500  }
501  //std::cout << "dist " << i << ": " << rought_dist << " modulo: " << modulo_dist << std::endl;
502  dist[i] += weight[j]*vpMath::sqr(modulo_dist);
503  }
504  }
505  // std::cout << "sol " << i << " [" << ok[i] << "] dist: " << dist[i] << " q: " << q_sol[i].t() << std::endl;
506  }
507  //std::cout << "dist: " << dist.t() << std::endl;
508  if (nbsol) {
509  for (unsigned int i=0; i<8; i++) {
510  if (ok[i] == true)
511  if (dist[i] < dist[sol]) sol = i;
512  }
513  // Update the inverse kinematics solution
514  q = q_sol[sol];
515 
516  // std::cout << "Nearest solution (" << sol << ") with distance ("
517  // << dist[sol] << "): " << q_sol[sol].t() << std::endl;
518  }
519  return nbsol;
520 
521 }
522 
577 unsigned int
578 vpViper::getInverseKinematics(const vpHomogeneousMatrix & fMc, vpColVector & q, const bool &verbose) const
579 {
582  vpHomogeneousMatrix eMc_;
583  this->get_wMe(wMe);
584  this->get_eMc(eMc_);
585  fMw = fMc * eMc_.inverse() * wMe.inverse();
586 
587  return (getInverseKinematicsWrist(fMw, q, verbose));
588 }
589 
616 vpViper::get_fMc (const vpColVector & q) const
617 {
619  get_fMc(q, fMc);
620 
621  return fMc;
622 }
623 
645 void
647 {
648 
649  // Compute the direct geometric model: fMe = transformation between
650  // fix and end effector frame.
652 
653  get_fMe(q, fMe);
654 
655  fMc = fMe * this->eMc;
656 
657  return;
658 }
659 
732 void
734 {
735  double q1 = q[0];
736  double q2 = q[1];
737  double q3 = q[2];
738  double q4 = q[3];
739  double q5 = q[4];
740  double q6 = q[5];
741  // We turn off the coupling since the measured positions are joint position
742  // taking into account the coupling factor. The coupling factor is relevant
743  // if positions are motor position.
744  // double q6 = q[5] + c56 * q[4];
745 
746 // std::cout << "q6 motor: " << q[5] << " rad "
747 // << vpMath::deg(q[5]) << " deg" << std::endl;
748 // std::cout << "q6 joint: " << q6 << " rad "
749 // << vpMath::deg(q6) << " deg" << std::endl;
750 
751  double c1 = cos(q1);
752  double s1 = sin(q1);
753  double c2 = cos(q2);
754  double s2 = sin(q2);
755  //double c3 = cos(q3);
756  //double s3 = sin(q3);
757  double c4 = cos(q4);
758  double s4 = sin(q4);
759  double c5 = cos(q5);
760  double s5 = sin(q5);
761  double c6 = cos(q6);
762  double s6 = sin(q6);
763  double c23 = cos(q2+q3);
764  double s23 = sin(q2+q3);
765 
766  fMe[0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
767  fMe[1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
768  fMe[2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
769 
770  fMe[0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
771  fMe[1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
772  fMe[2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
773 
774  fMe[0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
775  fMe[1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
776  fMe[2][2] = -s23*c4*s5+c23*c5;
777 
778  fMe[0][3] = c1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)-s1*s4*s5*d6;
779  fMe[1][3] = s1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)+c1*s4*s5*d6;
780  fMe[2][3] = s23*(a3-c4*s5*d6)+c23*(c5*d6+d4)-a2*s2+d1;
781 
782  // std::cout << "Effector position fMe: " << std::endl << fMe;
783 
784  return;
785 }
828 void
830 {
831  double q1 = q[0];
832  double q2 = q[1];
833  double q3 = q[2];
834  double q4 = q[3];
835  double q5 = q[4];
836  double q6 = q[5];
837  // We turn off the coupling since the measured positions are joint position
838  // taking into account the coupling factor. The coupling factor is relevant
839  // if positions are motor position.
840  // double q6 = q[5] + c56 * q[4];
841 
842 // std::cout << "q6 motor: " << q[5] << " rad "
843 // << vpMath::deg(q[5]) << " deg" << std::endl;
844 // std::cout << "q6 joint: " << q6 << " rad "
845 // << vpMath::deg(q6) << " deg" << std::endl;
846 
847  double c1 = cos(q1);
848  double s1 = sin(q1);
849  double c2 = cos(q2);
850  double s2 = sin(q2);
851  // double c3 = cos(q3);
852  //double s3 = sin(q3);
853  double c4 = cos(q4);
854  double s4 = sin(q4);
855  double c5 = cos(q5);
856  double s5 = sin(q5);
857  double c6 = cos(q6);
858  double s6 = sin(q6);
859  double c23 = cos(q2+q3);
860  double s23 = sin(q2+q3);
861 
862  fMw[0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
863  fMw[1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
864  fMw[2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
865 
866  fMw[0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
867  fMw[1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
868  fMw[2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
869 
870  fMw[0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
871  fMw[1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
872  fMw[2][2] = -s23*c4*s5+c23*c5;
873 
874  fMw[0][3] = c1*(-c23*a3+s23*d4+a1+a2*c2);
875  fMw[1][3] = s1*(-c23*a3+s23*d4+a1+a2*c2);
876  fMw[2][3] = s23*a3+c23*d4-a2*s2+d1;
877 
878  //std::cout << "Wrist position fMw: " << std::endl << fMw;
879 
880  return;
881 }
882 
893 void
895 {
896  // Set the rotation as identity
897  wMe.eye();
898 
899  // Set the translation
900  wMe[2][3] = d6;
901 }
902 
914 void
916 {
917  eMc_ = this->eMc;
918 }
919 
929 void
931 {
932  eMs.eye();
933  eMs[2][3] = -d7; // tz = -d7
934 }
935 
947 void
949 {
950  cMe = this->eMc.inverse();
951 }
952 
968 void
970 {
971  vpHomogeneousMatrix cMe ;
972  get_cMe(cMe) ;
973 
974  cVe.buildFrom(cMe) ;
975 
976  return;
977 }
978 
1001 void
1003 {
1004  vpMatrix V(6,6);
1005  V = 0;
1006  // Compute the first and last block of V
1007  vpHomogeneousMatrix fMw;
1008  get_fMw(q, fMw);
1009  vpRotationMatrix fRw;
1010  fMw.extract(fRw);
1011  vpRotationMatrix wRf;
1012  wRf = fRw.inverse();
1013  for (unsigned int i=0; i<3; i++ ) {
1014  for (unsigned int j=0; j<3; j++ ) {
1015  V[i][j] = V[i+3][j+3] = wRf[i][j];
1016  }
1017  }
1018  // Compute the second block of V
1019  vpHomogeneousMatrix wMe;
1020  get_wMe(wMe);
1021  vpHomogeneousMatrix eMw;
1022  eMw = wMe.inverse();
1023  vpTranslationVector etw;
1024  eMw.extract(etw);
1025  vpMatrix block2 = etw.skew()*wRf;
1026  for (unsigned int i=0; i<3; i++ ) {
1027  for (unsigned int j=0; j<3; j++ ) {
1028  V[i][j+3] = block2[i][j];
1029  }
1030  }
1031  // Compute eJe
1032  vpMatrix fJw;
1033  get_fJw(q, fJw);
1034  eJe = V * fJw;
1035 
1036  return;
1037 }
1038 
1039 
1087 void
1089 {
1090  double q1 = q[0];
1091  double q2 = q[1];
1092  double q3 = q[2];
1093  double q4 = q[3];
1094  double q5 = q[4];
1095 
1096  double c1 = cos(q1);
1097  double s1 = sin(q1);
1098  double c2 = cos(q2);
1099  double s2 = sin(q2);
1100  double c3 = cos(q3);
1101  double s3 = sin(q3);
1102  double c4 = cos(q4);
1103  double s4 = sin(q4);
1104  double c5 = cos(q5);
1105  double s5 = sin(q5);
1106  double c23 = cos(q2+q3);
1107  double s23 = sin(q2+q3);
1108 
1109  vpColVector J1(6);
1110  vpColVector J2(6);
1111  vpColVector J3(6);
1112  vpColVector J4(6);
1113  vpColVector J5(6);
1114  vpColVector J6(6);
1115 
1116  // Jacobian when d6 is set to zero
1117  J1[0] = -s1*(-c23*a3+s23*d4+a1+a2*c2);
1118  J1[1] = c1*(-c23*a3+s23*d4+a1+a2*c2);
1119  J1[2] = 0;
1120  J1[3] = 0;
1121  J1[4] = 0;
1122  J1[5] = 1;
1123 
1124  J2[0] = c1*(s23*a3+c23*d4-a2*s2);
1125  J2[1] = s1*(s23*a3+c23*d4-a2*s2);
1126  J2[2] = c23*a3-s23*d4-a2*c2;
1127  J2[3] = -s1;
1128  J2[4] = c1;
1129  J2[5] = 0;
1130 
1131  J3[0] = c1*(a3*(s2*c3+c2*s3)+(-s2*s3+c2*c3)*d4);
1132  J3[1] = s1*(a3*(s2*c3+c2*s3)+(-s2*s3+c2*c3)*d4);
1133  J3[2] = -a3*(s2*s3-c2*c3)-d4*(s2*c3+c2*s3);
1134  J3[3] = -s1;
1135  J3[4] = c1;
1136  J3[5] = 0;
1137 
1138  J4[0] = 0;
1139  J4[1] = 0;
1140  J4[2] = 0;
1141  J4[3] = c1*s23;
1142  J4[4] = s1*s23;
1143  J4[5] = c23;
1144 
1145  J5[0] = 0;
1146  J5[1] = 0;
1147  J5[2] = 0;
1148  J5[3] = -c23*c1*s4-s1*c4;
1149  J5[4] = c1*c4-c23*s1*s4;
1150  J5[5] = s23*s4;
1151 
1152  J6[0] = 0;
1153  J6[1] = 0;
1154  J6[2] = 0;
1155  J6[3] = (c1*c23*c4-s1*s4)*s5+c1*s23*c5;
1156  J6[4] = (s1*c23*c4+c1*s4)*s5+s1*s23*c5;
1157  J6[5] = -s23*c4*s5+c23*c5;
1158 
1159  fJw.resize(6,6) ;
1160  for (unsigned int i=0;i<6;i++) {
1161  fJw[i][0] = J1[i];
1162  fJw[i][1] = J2[i];
1163  fJw[i][2] = J3[i];
1164  fJw[i][3] = J4[i];
1165  fJw[i][4] = J5[i];
1166  fJw[i][5] = J6[i];
1167  }
1168  return;
1169 }
1193 void
1195 {
1196  vpMatrix V(6,6);
1197  V = 0;
1198  // Set the first and last block to identity
1199  for (unsigned int i=0; i<6; i++ )
1200  V[i][i] = 1;
1201 
1202  // Compute the second block of V
1203  vpHomogeneousMatrix fMw;
1204  get_fMw(q, fMw);
1205  vpRotationMatrix fRw;
1206  fMw.extract(fRw);
1207  vpHomogeneousMatrix wMe;
1208  get_wMe(wMe);
1209  vpHomogeneousMatrix eMw;
1210  eMw = wMe.inverse();
1211  vpTranslationVector etw;
1212  eMw.extract(etw);
1213  vpMatrix block2 = (fRw*etw).skew();
1214  // Set the second block
1215  for (unsigned int i=0; i<3; i++ )
1216  for (unsigned int j=0; j<3; j++ )
1217  V[i][j+3] = block2[i][j];
1218 
1219  // Compute fJe
1220  vpMatrix fJw;
1221  get_fJw(q, fJw);
1222  fJe = V * fJw;
1223 
1224  return;
1225 }
1226 
1227 
1237 {
1238  return joint_min;
1239 }
1240 
1250 {
1251  return joint_max;
1252 }
1253 
1264 double
1266 {
1267  return c56;
1268 }
1269 
1278 void
1280 {
1281  this->eMc = eMc_;
1282  this->eMc.extract(etc);
1283  vpRotationMatrix R(this->eMc);
1284  this->erc.buildFrom(R);
1285 }
1286 
1297 void
1299 {
1300  this->etc = etc_;
1301  this->erc = erc_;
1302  vpRotationMatrix eRc(erc);
1303  this->eMc.buildFrom(etc,eRc);
1304 }
1305 
1315 VISP_EXPORT std::ostream & operator << (std::ostream & os, const vpViper & viper)
1316 {
1317  vpRotationMatrix eRc;
1318  viper.eMc.extract(eRc);
1319  vpRxyzVector rxyz(eRc);
1320 
1321  // Convert joint limits in degrees
1322  vpColVector jmax = viper.joint_max;
1323  vpColVector jmin = viper.joint_min;
1324  jmax.rad2deg();
1325  jmin.rad2deg();
1326 
1327  os
1328  << "Joint Max (deg):" << std::endl
1329  << "\t" << jmax.t() << std::endl
1330 
1331  << "Joint Min (deg): " << std::endl
1332  << "\t" << jmin.t() << std::endl
1333 
1334  << "Coupling 5-6:" << std::endl
1335  << "\t" << viper.c56 << std::endl
1336 
1337  << "eMc: "<< std::endl
1338  << "\tTranslation (m): "
1339  << viper.eMc[0][3] << " "
1340  << viper.eMc[1][3] << " "
1341  << viper.eMc[2][3]
1342  << "\t" << std::endl
1343  << "\tRotation Rxyz (rad) : "
1344  << rxyz[0] << " "
1345  << rxyz[1] << " "
1346  << rxyz[2]
1347  << "\t" << std::endl
1348  << "\tRotation Rxyz (deg) : "
1349  << vpMath::deg(rxyz[0]) << " "
1350  << vpMath::deg(rxyz[1]) << " "
1351  << vpMath::deg(rxyz[2])
1352  << "\t" << std::endl;
1353 
1354  return os;
1355 }
void get_cVe(vpVelocityTwistMatrix &cVe) const
Definition: vpViper.cpp:969
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:97
double d7
for force/torque location
Definition: vpViper.h:165
vpRxyzVector buildFrom(const vpRotationMatrix &R)
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpViper.cpp:1002
void get_fMw(const vpColVector &q, vpHomogeneousMatrix &fMw) const
Definition: vpViper.cpp:829
double a3
for joint 3
Definition: vpViper.h:162
vpHomogeneousMatrix eMc
End effector to camera transformation.
Definition: vpViper.h:154
vpRotationMatrix inverse() const
Modelisation of the ADEPT Viper robot.
Definition: vpViper.h:112
double getCoupl56() const
Definition: vpViper.cpp:1265
void resize(const unsigned int nrows, const unsigned int ncols, const bool flagNullify=true)
Definition: vpArray2D.h:167
unsigned int getInverseKinematicsWrist(const vpHomogeneousMatrix &fMw, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:229
void get_wMe(vpHomogeneousMatrix &wMe) const
Definition: vpViper.cpp:894
Implementation of an homogeneous matrix and operations on such kind of matrices.
void get_eMc(vpHomogeneousMatrix &eMc) const
Definition: vpViper.cpp:915
void get_eMs(vpHomogeneousMatrix &eMs) const
Definition: vpViper.cpp:930
vpRxyzVector erc
Definition: vpViper.h:157
double a2
for joint 2
Definition: vpViper.h:161
Implementation of a rotation matrix and operations on such kind of matrices.
double d1
for joint 1
Definition: vpViper.h:160
double c56
Mechanical coupling between joint 5 and joint 6.
Definition: vpViper.h:166
double a1
Definition: vpViper.h:160
vpTranslationVector etc
Definition: vpViper.h:156
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
Definition: vpViper.cpp:1279
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double sqr(double x)
Definition: vpMath.h:110
vpRowVector t() const
vpColVector joint_max
Definition: vpViper.h:169
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:616
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
Definition: vpViper.cpp:733
friend std::ostream & operator<<(std::ostream &s, const vpArray2D< Type > &A)
Definition: vpArray2D.h:267
void get_fJw(const vpColVector &q, vpMatrix &fJw) const
Definition: vpViper.cpp:1088
Implementation of a velocity twist matrix and operations on such kind of matrices.
unsigned int getRows() const
Return the number of rows of the 2D array.
Definition: vpArray2D.h:152
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:578
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double rad(double deg)
Definition: vpMath.h:104
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpViper.cpp:1194
vpColVector getJointMin() const
Definition: vpViper.cpp:1236
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:948
static double deg(double rad)
Definition: vpMath.h:97
vpColVector getJointMax() const
Definition: vpViper.cpp:1249
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
vpHomogeneousMatrix inverse() const
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
double d4
for joint 4
Definition: vpViper.h:163
vpViper()
Definition: vpViper.cpp:66
vpHomogeneousMatrix getForwardKinematics(const vpColVector &q) const
Definition: vpViper.cpp:126
Class that consider the case of a translation vector.
void rad2deg()
Definition: vpColVector.h:210
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:151
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:225
double d6
for joint 6
Definition: vpViper.h:164
vpColVector joint_min
Definition: vpViper.h:170