ViSP  2.8.0
vpViper.cpp
1 /****************************************************************************
2  *
3  * $Id: vpViper.cpp 4206 2013-04-13 07:29:06Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2013 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  *
34  * Description:
35  * Interface for a generic ADEPT Viper (either 650 or 850) robot.
36  *
37  * Authors:
38  * Fabien Spindler
39  *
40  *****************************************************************************/
41 
52 #include <visp/vpDebug.h>
53 #include <visp/vpVelocityTwistMatrix.h>
54 #include <visp/vpRobotException.h>
55 #include <visp/vpCameraParameters.h>
56 #include <visp/vpRxyzVector.h>
57 #include <visp/vpTranslationVector.h>
58 #include <visp/vpRotationMatrix.h>
59 #include <visp/vpViper.h>
60 #include <cmath> // std::fabs
61 #include <limits> // numeric_limits
62 
63 const unsigned int vpViper::njoint = 6;
64 
71 {
72  // Default values are initialized
73 
74  // Denavit Hartenberg parameters
75  a1 = 0.075;
76  a2 = 0.365;
77  a3 = 0.090;
78  d1 = 0.335;
79  d4 = 0.405;
80  d6 = 0.080;
81  c56 = -341.33 / 9102.22;
82 
83  // Software joint limits in radians
85  joint_min[0] = vpMath::rad(-170);
86  joint_min[1] = vpMath::rad(-190);
87  joint_min[2] = vpMath::rad(-29);
88  joint_min[3] = vpMath::rad(-190);
89  joint_min[4] = vpMath::rad(-120);
90  joint_min[5] = vpMath::rad(-360);
92  joint_max[0] = vpMath::rad(170);
93  joint_max[1] = vpMath::rad(45);
94  joint_max[2] = vpMath::rad(256);
95  joint_max[3] = vpMath::rad(190);
96  joint_max[4] = vpMath::rad(120);
97  joint_max[5] = vpMath::rad(360);
98 
99  // End effector to camera transformation
100  eMc.setIdentity();
101 }
102 
103 
104 
105 
129 {
131  fMc = get_fMc(q);
132 
133  return fMc;
134 }
135 
150 bool
151 vpViper::convertJointPositionInLimits(unsigned int joint, const double &q, double &q_mod, const bool &verbose)
152 {
153  double eps = 0.01;
154  if (q >= joint_min[joint]-eps && q <= joint_max[joint]+eps ) {
155  q_mod = q;
156  return true;
157  }
158 
159  q_mod = q + 2*M_PI;
160  if (q_mod >= joint_min[joint]-eps && q_mod <= joint_max[joint]+eps ) {
161  return true;
162  }
163 
164  q_mod = q - 2*M_PI;
165  if (q_mod >= joint_min[joint]-eps && q_mod <= joint_max[joint]+eps ) {
166  return true;
167  }
168 
169  if (verbose) {
170  std::cout << "Joint " << joint << " not in limits: "
171  << this->joint_min[joint] << " < " << q << " < " << this->joint_max[joint] << std::endl;
172 
173  }
174 
175  return false;
176 }
177 
230 unsigned int
232 {
233  vpColVector q_sol[8];
234 
235  for (unsigned int i=0; i<8; i++)
236  q_sol[i].resize(6);
237 
238  double c1[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
239  double s1[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
240  double c3[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
241  double s3[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
242  double c23[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
243  double s23[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
244  double c4[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
245  double s4[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
246  double c5[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
247  double s5[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
248  double c6[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
249  double s6[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
250 
251  bool ok[8];
252 
253  if (q.getRows() != njoint)
254  q.resize(6);
255 
256  for (unsigned int i=0; i< 8; i++)
257  ok[i] = true;
258 
259  double px = fMw[0][3]; // a*c1
260  double py = fMw[1][3]; // a*s1
261  double pz = fMw[2][3];
262 
263  // Compute q1
264  double a_2 = px*px+py*py;
265  //if (a_2 == 0) {// singularity
266  if (std::fabs(a_2) <= std::numeric_limits<double>::epsilon()) {// singularity
267  c1[0] = cos(q[0]);
268  s1[0] = sin(q[0]);
269  c1[4] = cos(q[0]+M_PI);
270  s1[4] = sin(q[0]+M_PI);
271  }
272  else {
273  double a = sqrt(a_2);
274  c1[0] = px/a;
275  s1[0] = py/a;
276  c1[4] = -px/a;
277  s1[4] = -py/a;
278  }
279 
280  double q1_mod;
281  for(unsigned int i=0;i<8;i+=4) {
282  q_sol[i][0] = atan2(s1[i],c1[i]);
283  if (convertJointPositionInLimits(0, q_sol[i][0], q1_mod, verbose) == true) {
284  q_sol[i][0] = q1_mod;
285  for(unsigned int j=1;j<4;j++) {
286  c1[i+j] = c1[i];
287  s1[i+j] = s1[i];
288  q_sol[i+j][0] = q_sol[i][0];
289  }
290  }
291  else {
292  for(unsigned int j=1;j<4;j++)
293  ok[i+j] = false;
294  }
295  }
296 
297  // Compute q3
298  double K, q3_mod;
299  for(unsigned int i=0; i<8; i+=4) {
300  if(ok[i] == true) {
301  K = (px*px+py*py+pz*pz+a1*a1-a2*a2-a3*a3+d1*d1-d4*d4
302  - 2*(a1*c1[i]*px + a1*s1[i]*py + d1*pz)) / (2*a2);
303  double d4_a3_K = d4*d4+a3*a3-K*K;
304 
305  q_sol[i][2] = atan2(a3, d4) + atan2(K, sqrt(d4_a3_K));
306  q_sol[i+2][2] = atan2(a3, d4) + atan2(K, -sqrt(d4_a3_K));
307 
308  for (unsigned int j=0; j<4; j+=2) {
309  if (d4_a3_K < 0) {
310  for(unsigned int k=0; k<2; k++)
311  ok[i+j+k] = false;
312  }
313  else {
314  if (convertJointPositionInLimits(2, q_sol[i+j][2], q3_mod, verbose) == true) {
315  for(unsigned int k=0; k<2; k++) {
316  q_sol[i+j+k][2] = q3_mod;
317  c3[i+j+k] = cos(q3_mod);
318  s3[i+j+k] = sin(q3_mod);
319  }
320  }
321  else {
322  for(unsigned int k=0; k<2; k++)
323  ok[i+j+k] = false;
324  }
325  }
326  }
327  }
328  }
329  // std::cout << "ok apres q3: ";
330  // for (unsigned int i=0; i< 8; i++)
331  // std::cout << ok[i] << " ";
332  // std::cout << std::endl;
333 
334  // Compute q2
335  double q23[8], q2_mod;
336  for (unsigned int i=0; i<8; i+=2) {
337  if (ok[i] == true) {
338  // Compute q23 = q2+q3
339  c23[i] = (-(a3-a2*c3[i])*(c1[i]*px+s1[i]*py-a1)-(d1-pz)*(d4+a2*s3[i]))
340  / ( (c1[i]*px+s1[i]*py-a1)*(c1[i]*px+s1[i]*py-a1) +(d1-pz)*(d1-pz) );
341  s23[i] = ((d4+a2*s3[i])*(c1[i]*px+s1[i]*py-a1)-(d1-pz)*(a3-a2*c3[i]))
342  / ( (c1[i]*px+s1[i]*py-a1)*(c1[i]*px+s1[i]*py-a1) +(d1-pz)*(d1-pz) );
343  q23[i] = atan2(s23[i],c23[i]);
344  //std::cout << i << " c23 = " << c23[i] << " s23 = " << s23[i] << std::endl;
345  // q2 = q23 - q3
346  q_sol[i][1] = q23[i] - q_sol[i][2];
347 
348  if (convertJointPositionInLimits(1, q_sol[i][1], q2_mod, verbose) == true) {
349  for(unsigned int j=0; j<2; j++) {
350  q_sol[i+j][1] = q2_mod;
351  c23[i+j] = c23[i];
352  s23[i+j] = s23[i];
353  }
354  }
355  else {
356  for(unsigned int j=0; j<2; j++)
357  ok[i+j] = false;
358  }
359  }
360  }
361  // std::cout << "ok apres q2: ";
362  // for (unsigned int i=0; i< 8; i++)
363  // std::cout << ok[i] << " ";
364  // std::cout << std::endl;
365 
366  // Compute q4 as long as s5 != 0
367  double r13 = fMw[0][2];
368  double r23 = fMw[1][2];
369  double r33 = fMw[2][2];
370  double s4s5, c4s5, q4_mod, q5_mod;
371  for (unsigned int i=0; i<8; i+=2) {
372  if (ok[i] == true) {
373  s4s5 = -s1[i]*r13+c1[i]*r23;
374  c4s5 = c1[i]*c23[i]*r13+s1[i]*c23[i]*r23-s23[i]*r33;
375  if (fabs(s4s5) < vpMath::rad(0.5) && fabs(c4s5) < vpMath::rad(0.5)) {
376  // s5 = 0
377  c5[i] = c1[i]*s23[i]*r13+s1[i]*s23[i]*r23+c23[i]*r33;
378  //std::cout << "Singularity: s5 near 0: ";
379  if (c5[i] > 0.)
380  q_sol[i][4] = 0.0;
381  else
382  q_sol[i][4] = M_PI;
383 
384  if (convertJointPositionInLimits(4, q_sol[i][4], q5_mod, verbose) == true) {
385  for(unsigned int j=0; j<2; j++) {
386  q_sol[i+j][3] = q[3]; // keep current q4
387  q_sol[i+j][4] = q5_mod;
388  c4[i] = cos(q_sol[i+j][3]);
389  s4[i] = sin(q_sol[i+j][3]);
390  }
391  }
392  else {
393  for(unsigned int j=0; j<2; j++)
394  ok[i+j] = false;
395  }
396  }
397  else {
398  // s5 != 0
399  //if (c4s5 == 0) {
400  if (std::fabs(c4s5) <= std::numeric_limits<double>::epsilon()) {
401  // c4 = 0
402  // vpTRACE("c4 = 0");
403  // q_sol[i][3] = q[3]; // keep current position
404  q_sol[i][3] = atan2(s4s5, c4s5);
405  }
406  else {
407  q_sol[i][3] = atan2(s4s5, c4s5);
408  }
409  if (convertJointPositionInLimits(3, q_sol[i][3], q4_mod, verbose) == true) {
410  q_sol[i][3] = q4_mod;
411  c4[i] = cos(q4_mod);
412  s4[i] = sin(q4_mod);
413  }
414  else {
415  ok[i] = false;
416  }
417  if (q_sol[i][3] > 0.)
418  q_sol[i+1][3] = q_sol[i][3] + M_PI;
419  else
420  q_sol[i+1][3] = q_sol[i][3] - M_PI;
421  if (convertJointPositionInLimits(3, q_sol[i+1][3], q4_mod, verbose) == true) {
422  q_sol[i+1][3] = q4_mod;
423  c4[i+1] = cos(q4_mod);
424  s4[i+1] = sin(q4_mod);
425  }
426  else {
427  ok[i+1] = false;
428  }
429 
430  // Compute q5
431  for (unsigned int j=0; j<2; j++) {
432  if (ok[i+j] == true) {
433  c5[i+j] = c1[i+j]*s23[i+j]*r13+s1[i+j]*s23[i+j]*r23+c23[i+j]*r33;
434  s5[i+j] = (c1[i+j]*c23[i+j]*c4[i+j]-s1[i+j]*s4[i+j])*r13
435  +(s1[i+j]*c23[i+j]*c4[i+j]+c1[i+j]*s4[i+j])*r23-s23[i+j]*c4[i+j]*r33;
436 
437  q_sol[i+j][4] = atan2(s5[i+j], c5[i+j]);
438  if (convertJointPositionInLimits(4, q_sol[i+j][4], q5_mod, verbose) == true) {
439  q_sol[i+j][4] = q5_mod;
440  }
441  else {
442 
443  ok[i+j] = false;
444  }
445  }
446  }
447  }
448  }
449  }
450 
451  // Compute q6
452  // 4 solutions for q6 and 4 more solutions by flipping the wrist (see below)
453  double r12 = fMw[0][1];
454  double r22 = fMw[1][1];
455  double r32 = fMw[2][1];
456  double q6_mod;
457  for (unsigned int i=0; i<8; i++) {
458  c6[i] = -(c1[i]*c23[i]*s4[i]+s1[i]*c4[i])*r12
459  +(c1[i]*c4[i]-s1[i]*c23[i]*s4[i])*r22+s23[i]*s4[i]*r32;
460  s6[i] = -(c1[i]*c23[i]*c4[i]*c5[i]-c1[i]*s23[i]*s5[i]
461  -s1[i]*s4[i]*c5[i])*r12
462  -(s1[i]*c23[i]*c4[i]*c5[i]-s1[i]*s23[i]*s5[i]+c1[i]*s4[i]*c5[i])*r22
463  +(c23[i]*s5[i]+s23[i]*c4[i]*c5[i])*r32;
464 
465  q_sol[i][5] = atan2(s6[i], c6[i]);
466  if (convertJointPositionInLimits(5, q_sol[i][5], q6_mod, verbose) == true) {
467  q_sol[i][5] = q6_mod;
468  }
469  else {
470  ok[i] = false;
471  }
472  }
473 
474  // Select the best config in terms of distance from the current position
475  unsigned int nbsol = 0;
476  unsigned int sol = 0;
477  vpColVector dist(8);
478  for (unsigned int i=0; i<8; i++) {
479  if (ok[i] == true) {
480  nbsol ++;
481  sol = i;
482  // dist[i] = vpColVector::distance(q, q_sol[i]);
483  vpColVector weight(6);
484  weight = 1;
485  weight[0] = 8;
486  weight[1] = weight[2] = 4;
487  dist[i] = 0;
488  for (unsigned int j=0; j< 6; j++) {
489  double rought_dist = q[j]- q_sol[i][j];
490  double modulo_dist = rought_dist;
491  if (rought_dist > 0) {
492  if (fabs(rought_dist - 2*M_PI) < fabs(rought_dist))
493  modulo_dist = rought_dist - 2*M_PI;
494  }
495  else {
496  if (fabs(rought_dist + 2*M_PI) < fabs(rought_dist))
497  modulo_dist = rought_dist + 2*M_PI;
498  }
499  //std::cout << "dist " << i << ": " << rought_dist << " modulo: " << modulo_dist << std::endl;
500  dist[i] += weight[j]*vpMath::sqr(modulo_dist);
501  }
502  }
503  // std::cout << "sol " << i << " [" << ok[i] << "] dist: " << dist[i] << " q: " << q_sol[i].t() << std::endl;
504  }
505  //std::cout << "dist: " << dist.t() << std::endl;
506  if (nbsol) {
507  for (unsigned int i=0; i<8; i++) {
508  if (ok[i] == true)
509  if (dist[i] < dist[sol]) sol = i;
510  }
511  // Update the inverse kinematics solution
512  q = q_sol[sol];
513 
514  // std::cout << "Nearest solution (" << sol << ") with distance ("
515  // << dist[sol] << "): " << q_sol[sol].t() << std::endl;
516  }
517  return nbsol;
518 
519 }
520 
575 unsigned int
576 vpViper::getInverseKinematics(const vpHomogeneousMatrix & fMc, vpColVector & q, const bool &verbose)
577 {
581  this->get_wMe(wMe);
582  this->get_eMc(eMc);
583  fMw = fMc * eMc.inverse() * wMe.inverse();
584 
585  return (getInverseKinematicsWrist(fMw, q, verbose));
586 }
587 
615 {
617  get_fMc(q, fMc);
618 
619  return fMc;
620 }
621 
643 void
645 {
646 
647  // Compute the direct geometric model: fMe = transformation between
648  // fix and end effector frame.
650 
651  get_fMe(q, fMe);
652 
653  fMc = fMe * this->eMc;
654 
655  return;
656 }
657 
730 void
732 {
733  double q1 = q[0];
734  double q2 = q[1];
735  double q3 = q[2];
736  double q4 = q[3];
737  double q5 = q[4];
738  double q6 = q[5];
739  // We turn off the coupling since the measured positions are joint position
740  // taking into account the coupling factor. The coupling factor is relevant
741  // if positions are motor position.
742  // double q6 = q[5] + c56 * q[4];
743 
744 // std::cout << "q6 motor: " << q[5] << " rad "
745 // << vpMath::deg(q[5]) << " deg" << std::endl;
746 // std::cout << "q6 joint: " << q6 << " rad "
747 // << vpMath::deg(q6) << " deg" << std::endl;
748 
749  double c1 = cos(q1);
750  double s1 = sin(q1);
751  double c2 = cos(q2);
752  double s2 = sin(q2);
753  //double c3 = cos(q3);
754  //double s3 = sin(q3);
755  double c4 = cos(q4);
756  double s4 = sin(q4);
757  double c5 = cos(q5);
758  double s5 = sin(q5);
759  double c6 = cos(q6);
760  double s6 = sin(q6);
761  double c23 = cos(q2+q3);
762  double s23 = sin(q2+q3);
763 
764  fMe[0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
765  fMe[1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
766  fMe[2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
767 
768  fMe[0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
769  fMe[1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
770  fMe[2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
771 
772  fMe[0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
773  fMe[1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
774  fMe[2][2] = -s23*c4*s5+c23*c5;
775 
776  fMe[0][3] = c1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)-s1*s4*s5*d6;
777  fMe[1][3] = s1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)+c1*s4*s5*d6;
778  fMe[2][3] = s23*(a3-c4*s5*d6)+c23*(c5*d6+d4)-a2*s2+d1;
779 
780  // std::cout << "Effector position fMe: " << std::endl << fMe;
781 
782  return;
783 }
826 void
828 {
829  double q1 = q[0];
830  double q2 = q[1];
831  double q3 = q[2];
832  double q4 = q[3];
833  double q5 = q[4];
834  double q6 = q[5];
835  // We turn off the coupling since the measured positions are joint position
836  // taking into account the coupling factor. The coupling factor is relevant
837  // if positions are motor position.
838  // double q6 = q[5] + c56 * q[4];
839 
840 // std::cout << "q6 motor: " << q[5] << " rad "
841 // << vpMath::deg(q[5]) << " deg" << std::endl;
842 // std::cout << "q6 joint: " << q6 << " rad "
843 // << vpMath::deg(q6) << " deg" << std::endl;
844 
845  double c1 = cos(q1);
846  double s1 = sin(q1);
847  double c2 = cos(q2);
848  double s2 = sin(q2);
849  // double c3 = cos(q3);
850  //double s3 = sin(q3);
851  double c4 = cos(q4);
852  double s4 = sin(q4);
853  double c5 = cos(q5);
854  double s5 = sin(q5);
855  double c6 = cos(q6);
856  double s6 = sin(q6);
857  double c23 = cos(q2+q3);
858  double s23 = sin(q2+q3);
859 
860 
861  fMw[0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
862  fMw[1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
863  fMw[2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
864 
865  fMw[0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
866  fMw[1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
867  fMw[2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
868 
869  fMw[0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
870  fMw[1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
871  fMw[2][2] = -s23*c4*s5+c23*c5;
872 
873  fMw[0][3] = c1*(-c23*a3+s23*d4+a1+a2*c2);
874  fMw[1][3] = s1*(-c23*a3+s23*d4+a1+a2*c2);
875  fMw[2][3] = s23*a3+c23*d4-a2*s2+d1;
876 
877  //std::cout << "Wrist position fMw: " << std::endl << fMw;
878 
879  return;
880 }
881 
892 void
894 {
895  // Set the rotation as identity
896  wMe.setIdentity();
897 
898  // Set the translation
899  wMe[2][3] = d6;
900 }
901 
913 void
915 {
916  eMc = this->eMc;
917 }
918 
930 void
932 {
933  cMe = this->eMc.inverse();
934 }
935 
951 void
953 {
954  vpHomogeneousMatrix cMe ;
955  get_cMe(cMe) ;
956 
957  cVe.buildFrom(cMe) ;
958 
959  return;
960 }
961 
984 void
986 {
987  vpMatrix V(6,6);
988  V = 0;
989  // Compute the first and last block of V
991  get_fMw(q, fMw);
992  vpRotationMatrix fRw;
993  fMw.extract(fRw);
994  vpRotationMatrix wRf;
995  wRf = fRw.inverse();
996  for (unsigned int i=0; i<3; i++ ) {
997  for (unsigned int j=0; j<3; j++ ) {
998  V[i][j] = V[i+3][j+3] = wRf[i][j];
999  }
1000  }
1001  // Compute the second block of V
1002  vpHomogeneousMatrix wMe;
1003  get_wMe(wMe);
1004  vpHomogeneousMatrix eMw;
1005  eMw = wMe.inverse();
1006  vpTranslationVector etw;
1007  eMw.extract(etw);
1008  vpMatrix block2 = etw.skew()*wRf;
1009  for (unsigned int i=0; i<3; i++ ) {
1010  for (unsigned int j=0; j<3; j++ ) {
1011  V[i][j+3] = block2[i][j];
1012  }
1013  }
1014  // Compute eJe
1015  vpMatrix fJw;
1016  get_fJw(q, fJw);
1017  eJe = V * fJw;
1018 
1019  return;
1020 }
1021 
1022 
1070 void
1072 {
1073  double q1 = q[0];
1074  double q2 = q[1];
1075  double q3 = q[2];
1076  double q4 = q[3];
1077  double q5 = q[4];
1078 
1079  double c1 = cos(q1);
1080  double s1 = sin(q1);
1081  double c2 = cos(q2);
1082  double s2 = sin(q2);
1083  double c3 = cos(q3);
1084  double s3 = sin(q3);
1085  double c4 = cos(q4);
1086  double s4 = sin(q4);
1087  double c5 = cos(q5);
1088  double s5 = sin(q5);
1089  double c23 = cos(q2+q3);
1090  double s23 = sin(q2+q3);
1091 
1092  vpColVector J1(6);
1093  vpColVector J2(6);
1094  vpColVector J3(6);
1095  vpColVector J4(6);
1096  vpColVector J5(6);
1097  vpColVector J6(6);
1098 
1099  // Jacobian when d6 is set to zero
1100  J1[0] = -s1*(-c23*a3+s23*d4+a1+a2*c2);
1101  J1[1] = c1*(-c23*a3+s23*d4+a1+a2*c2);
1102  J1[2] = 0;
1103  J1[3] = 0;
1104  J1[4] = 0;
1105  J1[5] = 1;
1106 
1107  J2[0] = c1*(s23*a3+c23*d4-a2*s2);
1108  J2[1] = s1*(s23*a3+c23*d4-a2*s2);
1109  J2[2] = c23*a3-s23*d4-a2*c2;
1110  J2[3] = -s1;
1111  J2[4] = c1;
1112  J2[5] = 0;
1113 
1114  J3[0] = c1*(a3*(s2*c3+c2*s3)+(-s2*s3+c2*c3)*d4);
1115  J3[1] = s1*(a3*(s2*c3+c2*s3)+(-s2*s3+c2*c3)*d4);
1116  J3[2] = -a3*(s2*s3-c2*c3)-d4*(s2*c3+c2*s3);
1117  J3[3] = -s1;
1118  J3[4] = c1;
1119  J3[5] = 0;
1120 
1121  J4[0] = 0;
1122  J4[1] = 0;
1123  J4[2] = 0;
1124  J4[3] = c1*s23;
1125  J4[4] = s1*s23;
1126  J4[5] = c23;
1127 
1128  J5[0] = 0;
1129  J5[1] = 0;
1130  J5[2] = 0;
1131  J5[3] = -c23*c1*s4-s1*c4;
1132  J5[4] = c1*c4-c23*s1*s4;
1133  J5[5] = s23*s4;
1134 
1135  J6[0] = 0;
1136  J6[1] = 0;
1137  J6[2] = 0;
1138  J6[3] = (c1*c23*c4-s1*s4)*s5+c1*s23*c5;
1139  J6[4] = (s1*c23*c4+c1*s4)*s5+s1*s23*c5;
1140  J6[5] = -s23*c4*s5+c23*c5;
1141 
1142  fJw.resize(6,6) ;
1143  for (unsigned int i=0;i<6;i++) {
1144  fJw[i][0] = J1[i];
1145  fJw[i][1] = J2[i];
1146  fJw[i][2] = J3[i];
1147  fJw[i][3] = J4[i];
1148  fJw[i][4] = J5[i];
1149  fJw[i][5] = J6[i];
1150  }
1151  return;
1152 }
1176 void
1178 {
1179  vpMatrix V(6,6);
1180  V = 0;
1181  // Set the first and last block to identity
1182  for (unsigned int i=0; i<6; i++ )
1183  V[i][i] = 1;
1184 
1185  // Compute the second block of V
1186  vpHomogeneousMatrix fMw;
1187  get_fMw(q, fMw);
1188  vpRotationMatrix fRw;
1189  fMw.extract(fRw);
1190  vpHomogeneousMatrix wMe;
1191  get_wMe(wMe);
1192  vpHomogeneousMatrix eMw;
1193  eMw = wMe.inverse();
1194  vpTranslationVector etw;
1195  eMw.extract(etw);
1196  vpMatrix block2 = (fRw*etw).skew();
1197  // Set the second block
1198  for (unsigned int i=0; i<3; i++ )
1199  for (unsigned int j=0; j<3; j++ )
1200  V[i][j+3] = block2[i][j];
1201 
1202  // Compute fJe
1203  vpMatrix fJw;
1204  get_fJw(q, fJw);
1205  fJe = V * fJw;
1206 
1207  return;
1208 }
1209 
1210 
1220 {
1221  return joint_min;
1222 }
1223 
1233 {
1234  return joint_max;
1235 }
1236 
1247 double
1249 {
1250  return c56;
1251 }
1252 
1253 
1254 
1264 std::ostream & operator << (std::ostream & os, const vpViper & viper)
1265 {
1266  vpRotationMatrix eRc;
1267  viper.eMc.extract(eRc);
1268  vpRxyzVector rxyz(eRc);
1269 
1270  // Convert joint limits in degrees
1271  vpColVector jmax = viper.joint_max;
1272  vpColVector jmin = viper.joint_min;
1273  jmax.rad2deg();
1274  jmin.rad2deg();
1275 
1276  os
1277  << "Joint Max (deg):" << std::endl
1278  << "\t" << jmax.t() << std::endl
1279 
1280  << "Joint Min (deg): " << std::endl
1281  << "\t" << jmin.t() << std::endl
1282 
1283  << "Coupling 5-6:" << std::endl
1284  << "\t" << viper.c56 << std::endl
1285 
1286  << "eMc: "<< std::endl
1287  << "\tTranslation (m): "
1288  << viper.eMc[0][3] << " "
1289  << viper.eMc[1][3] << " "
1290  << viper.eMc[2][3]
1291  << "\t" << std::endl
1292  << "\tRotation Rxyz (rad) : "
1293  << rxyz[0] << " "
1294  << rxyz[1] << " "
1295  << rxyz[2]
1296  << "\t" << std::endl
1297  << "\tRotation Rxyz (deg) : "
1298  << vpMath::deg(rxyz[0]) << " "
1299  << vpMath::deg(rxyz[1]) << " "
1300  << vpMath::deg(rxyz[2])
1301  << "\t" << std::endl;
1302 
1303  return os;
1304 }
1305 /*
1306  * Local variables:
1307  * c-basic-offset: 2
1308  * End:
1309  */
Definition of the vpMatrix class.
Definition: vpMatrix.h:96
double a3
for joint 3
Definition: vpViper.h:155
void resize(const unsigned int nrows, const unsigned int ncols, const bool nullify=true)
Definition: vpMatrix.cpp:174
vpHomogeneousMatrix eMc
End effector to camera transformation.
Definition: vpViper.h:147
vpRotationMatrix inverse() const
invert the rotation matrix
Modelisation of the ADEPT Viper robot.
Definition: vpViper.h:111
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
void get_eJe(const vpColVector &q, vpMatrix &eJe)
Definition: vpViper.cpp:985
void setIdentity()
Basic initialisation (identity)
vpColVector getJointMin()
Definition: vpViper.cpp:1219
double a2
for joint 2
Definition: vpViper.h:154
The vpRotationMatrix considers the particular case of a rotation matrix.
double d1
for joint 1
Definition: vpViper.h:153
double c56
Mechanical coupling between joint 5 and joint 6.
Definition: vpViper.h:158
double a1
Definition: vpViper.h:153
void get_eMc(vpHomogeneousMatrix &eMc)
Definition: vpViper.cpp:914
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double sqr(double x)
Definition: vpMath.h:106
vpRowVector t() const
transpose of Vector
vpColVector joint_max
Definition: vpViper.h:161
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe)
Definition: vpViper.cpp:731
void extract(vpRotationMatrix &R) const
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
VISP_EXPORT std::ostream & operator<<(std::ostream &os, const vpImagePoint &ip)
Definition: vpImagePoint.h:529
static double rad(double deg)
Definition: vpMath.h:100
void get_fJe(const vpColVector &q, vpMatrix &fJe)
Definition: vpViper.cpp:1177
vpColVector getJointMax()
Definition: vpViper.cpp:1232
static double deg(double rad)
Definition: vpMath.h:93
void get_wMe(vpHomogeneousMatrix &wMe)
Definition: vpViper.cpp:893
Class that provides a data structure for the column vectors as well as a set of operations on these v...
Definition: vpColVector.h:72
vpHomogeneousMatrix inverse() const
unsigned int getInverseKinematicsWrist(const vpHomogeneousMatrix &fMw, vpColVector &q, const bool &verbose=false)
Definition: vpViper.cpp:231
void get_fJw(const vpColVector &q, vpMatrix &fJw)
Definition: vpViper.cpp:1071
void get_cMe(vpHomogeneousMatrix &cMe)
Definition: vpViper.cpp:931
Class that consider the case of the Euler angle using the x-y-z convention, where are respectively ...
Definition: vpRxyzVector.h:152
double d4
for joint 4
Definition: vpViper.h:156
vpViper()
Definition: vpViper.cpp:70
void get_cVe(vpVelocityTwistMatrix &cVe)
Definition: vpViper.cpp:952
unsigned int getRows() const
Return the number of rows of the matrix.
Definition: vpMatrix.h:157
Class that consider the case of a translation vector.
void rad2deg()
Definition: vpColVector.h:177
double getCoupl56()
Definition: vpViper.cpp:1248
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false)
Definition: vpViper.cpp:576
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:144
vpHomogeneousMatrix get_fMc(const vpColVector &q)
Definition: vpViper.cpp:614
vpHomogeneousMatrix getForwardKinematics(const vpColVector &q)
Definition: vpViper.cpp:128
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:94
void get_fMw(const vpColVector &q, vpHomogeneousMatrix &fMw)
Definition: vpViper.cpp:827
double d6
for joint 6
Definition: vpViper.h:157
vpColVector joint_min
Definition: vpViper.h:162