ViSP  2.6.2
vpViper.cpp
1 /****************************************************************************
2  *
3  * $Id: vpViper.cpp 3834 2012-07-03 10:36:30Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2012 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)
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  return false;
170 }
171 
220 unsigned int
222 {
223  vpColVector q_sol[8];
224 
225  for (unsigned int i=0; i<8; i++)
226  q_sol[i].resize(6);
227 
228  double c1[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
229  double s1[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
230  double c3[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
231  double s3[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
232  double c23[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
233  double s23[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
234  double c4[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
235  double s4[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
236  double c5[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
237  double s5[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
238  double c6[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
239  double s6[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
240 
241  bool ok[8];
242 
243  if (q.getRows() != njoint)
244  q.resize(6);
245 
246  for (unsigned int i=0; i< 8; i++)
247  ok[i] = true;
248 
249  double px = fMw[0][3]; // a*c1
250  double py = fMw[1][3]; // a*s1
251  double pz = fMw[2][3];
252 
253  // Compute q1
254  double a_2 = px*px+py*py;
255  //if (a_2 == 0) {// singularity
256  if (std::fabs(a_2) <= std::numeric_limits<double>::epsilon()) {// singularity
257  c1[0] = cos(q[0]);
258  s1[0] = sin(q[0]);
259  c1[4] = cos(q[0]+M_PI);
260  s1[4] = sin(q[0]+M_PI);
261  }
262  else {
263  double a = sqrt(a_2);
264  c1[0] = px/a;
265  s1[0] = py/a;
266  c1[4] = -px/a;
267  s1[4] = -py/a;
268  }
269 
270  double q1_mod;
271  for(unsigned int i=0;i<8;i+=4) {
272  q_sol[i][0] = atan2(s1[i],c1[i]);
273  if (convertJointPositionInLimits(0, q_sol[i][0], q1_mod) == true) {
274  q_sol[i][0] = q1_mod;
275  for(unsigned int j=1;j<4;j++) {
276  c1[i+j] = c1[i];
277  s1[i+j] = s1[i];
278  q_sol[i+j][0] = q_sol[i][0];
279  }
280  }
281  else {
282  for(unsigned int j=1;j<4;j++)
283  ok[i+j] = false;
284  }
285  }
286 
287 // std::cout << "ok apres q1: ";
288 // for (unsigned int i=0; i< 8; i++)
289 // std::cout << ok[i] << " ";
290 // std::cout << std::endl;
291 
292  // Compute q3
293  double K, q3_mod;
294  for(unsigned int i=0; i<8; i+=4) {
295  if(ok[i] == true) {
296  K = (px*px+py*py+pz*pz+a1*a1-a2*a2-a3*a3+d1*d1-d4*d4
297  - 2*(a1*c1[i]*px + a1*s1[i]*py + d1*pz)) / (2*a2);
298  q_sol[i][2] = atan2(a3, d4) + atan2(K, sqrt(d4*d4+a3*a3-K*K));
299  q_sol[i+2][2] = atan2(a3, d4) + atan2(K, -sqrt(d4*d4+a3*a3-K*K));
300 
301  for (unsigned int j=0; j<4; j+=2) {
302  if (convertJointPositionInLimits(2, q_sol[i+j][2], q3_mod) == true) {
303  for(unsigned int k=0; k<2; k++) {
304  q_sol[i+j+k][2] = q3_mod;
305  c3[i+j+k] = cos(q3_mod);
306  s3[i+j+k] = sin(q3_mod);
307  }
308  }
309  else {
310  for(unsigned int k=0; k<2; k++)
311  ok[i+j+k] = false;
312  }
313  }
314  }
315  }
316 // std::cout << "ok apres q3: ";
317 // for (unsigned int i=0; i< 8; i++)
318 // std::cout << ok[i] << " ";
319 // std::cout << std::endl;
320 
321  // Compute q2
322  double q23[8], q2_mod;
323  for (unsigned int i=0; i<8; i+=2) {
324  if (ok[i] == true) {
325  // Compute q23 = q2+q3
326  c23[i] = (-(a3-a2*c3[i])*(c1[i]*px+s1[i]*py-a1)-(d1-pz)*(d4+a2*s3[i]))
327  / ( (c1[i]*px+s1[i]*py-a1)*(c1[i]*px+s1[i]*py-a1) +(d1-pz)*(d1-pz) );
328  s23[i] = ((d4+a2*s3[i])*(c1[i]*px+s1[i]*py-a1)-(d1-pz)*(a3-a2*c3[i]))
329  / ( (c1[i]*px+s1[i]*py-a1)*(c1[i]*px+s1[i]*py-a1) +(d1-pz)*(d1-pz) );
330  q23[i] = atan2(s23[i],c23[i]);
331  //std::cout << i << " c23 = " << c23[i] << " s23 = " << s23[i] << std::endl;
332  // q2 = q23 - q3
333  q_sol[i][1] = q23[i] - q_sol[i][2];
334 
335  if (convertJointPositionInLimits(1, q_sol[i][1], q2_mod) == true) {
336  for(unsigned int j=0; j<2; j++) {
337  q_sol[i+j][1] = q2_mod;
338  c23[i+j] = c23[i];
339  s23[i+j] = s23[i];
340  }
341  }
342  else {
343  for(unsigned int j=0; j<2; j++)
344  ok[i+j] = false;
345  }
346  }
347  }
348 // std::cout << "ok apres q2: ";
349 // for (unsigned int i=0; i< 8; i++)
350 // std::cout << ok[i] << " ";
351 // std::cout << std::endl;
352 
353  // Compute q4 as long as s5 != 0
354  double r13 = fMw[0][2];
355  double r23 = fMw[1][2];
356  double r33 = fMw[2][2];
357  double s4s5, c4s5, q4_mod, q5_mod;
358  for (unsigned int i=0; i<8; i+=2) {
359  if (ok[i] == true) {
360  s4s5 = -s1[i]*r13+c1[i]*r23;
361  c4s5 = c1[i]*c23[i]*r13+s1[i]*c23[i]*r23-s23[i]*r33;
362  if (fabs(s4s5) < vpMath::rad(0.5) && fabs(c4s5) < vpMath::rad(0.5)) {
363  // s5 = 0
364  c5[i] = c1[i]*s23[i]*r13+s1[i]*s23[i]*r23+c23[i]*r33;
365  //std::cout << "Singularity: s5 near 0: ";
366  if (c5[i] > 0.)
367  q_sol[i][4] = 0.0;
368  else
369  q_sol[i][4] = M_PI;
370 
371  if (convertJointPositionInLimits(4, q_sol[i][4], q5_mod) == true) {
372  for(unsigned int j=0; j<2; j++) {
373  q_sol[i+j][3] = q[3]; // keep current q4
374  q_sol[i+j][4] = q5_mod;
375  c4[i] = cos(q_sol[i+j][3]);
376  s4[i] = sin(q_sol[i+j][3]);
377  }
378  }
379  else {
380  for(unsigned int j=0; j<2; j++)
381  ok[i+j] = false;
382  }
383  }
384  else {
385  // s5 != 0
386  //if (c4s5 == 0) {
387  if (std::fabs(c4s5) <= std::numeric_limits<double>::epsilon()) {
388  // c4 = 0
389  // vpTRACE("c4 = 0");
390  // q_sol[i][3] = q[3]; // keep current position
391  q_sol[i][3] = atan2(s4s5, c4s5);
392  }
393  else {
394  q_sol[i][3] = atan2(s4s5, c4s5);
395  }
396  if (convertJointPositionInLimits(3, q_sol[i][3], q4_mod) == true) {
397  q_sol[i][3] = q4_mod;
398  c4[i] = cos(q4_mod);
399  s4[i] = sin(q4_mod);
400  }
401  else {
402  ok[i] = false;
403  }
404  if (q_sol[i][3] > 0.)
405  q_sol[i+1][3] = q_sol[i][3] + M_PI;
406  else
407  q_sol[i+1][3] = q_sol[i][3] - M_PI;
408  if (convertJointPositionInLimits(3, q_sol[i+1][3], q4_mod) == true) {
409  q_sol[i+1][3] = q4_mod;
410  c4[i+1] = cos(q4_mod);
411  s4[i+1] = sin(q4_mod);
412  }
413  else {
414  ok[i+1] = false;
415  }
416 
417  // Compute q5
418  for (unsigned int j=0; j<2; j++) {
419  if (ok[i+j] == true) {
420  c5[i+j] = c1[i+j]*s23[i+j]*r13+s1[i+j]*s23[i+j]*r23+c23[i+j]*r33;
421  s5[i+j] = (c1[i+j]*c23[i+j]*c4[i+j]-s1[i+j]*s4[i+j])*r13
422  +(s1[i+j]*c23[i+j]*c4[i+j]+c1[i+j]*s4[i+j])*r23-s23[i+j]*c4[i+j]*r33;
423 
424  q_sol[i+j][4] = atan2(s5[i+j], c5[i+j]);
425  if (convertJointPositionInLimits(4, q_sol[i+j][4], q5_mod) == true) {
426  q_sol[i+j][4] = q5_mod;
427  }
428  else {
429 
430  ok[i+j] = false;
431  }
432  }
433  }
434  }
435  }
436  }
437 
438  // Compute q6
439  // 4 solutions for q6 and 4 more solutions by flipping the wrist (see below)
440  double r12 = fMw[0][1];
441  double r22 = fMw[1][1];
442  double r32 = fMw[2][1];
443  double q6_mod;
444  for (unsigned int i=0; i<8; i++) {
445  c6[i] = -(c1[i]*c23[i]*s4[i]+s1[i]*c4[i])*r12
446  +(c1[i]*c4[i]-s1[i]*c23[i]*s4[i])*r22+s23[i]*s4[i]*r32;
447  s6[i] = -(c1[i]*c23[i]*c4[i]*c5[i]-c1[i]*s23[i]*s5[i]
448  -s1[i]*s4[i]*c5[i])*r12
449  -(s1[i]*c23[i]*c4[i]*c5[i]-s1[i]*s23[i]*s5[i]+c1[i]*s4[i]*c5[i])*r22
450  +(c23[i]*s5[i]+s23[i]*c4[i]*c5[i])*r32;
451 
452  q_sol[i][5] = atan2(s6[i], c6[i]);
453  if (convertJointPositionInLimits(5, q_sol[i][5], q6_mod) == true) {
454  q_sol[i][5] = q6_mod;
455  }
456  else {
457  ok[i] = false;
458  }
459  }
460 
461  // Select the best config in terms of distance from the current position
462  unsigned int nbsol = 0;
463  unsigned int sol = 0;
464  vpColVector dist(8);
465  for (unsigned int i=0; i<8; i++) {
466  if (ok[i] == true) {
467  nbsol ++;
468  sol = i;
469  // dist[i] = vpColVector::distance(q, q_sol[i]);
470  vpColVector weight(6);
471  weight = 1;
472  weight[0] = 8;
473  weight[1] = weight[2] = 4;
474  dist[i] = 0;
475  for (unsigned int j=0; j< 6; j++) {
476  double rought_dist = q[j]- q_sol[i][j];
477  double modulo_dist = rought_dist;
478  if (rought_dist > 0) {
479  if (fabs(rought_dist - 2*M_PI) < fabs(rought_dist))
480  modulo_dist = rought_dist - 2*M_PI;
481  }
482  else {
483  if (fabs(rought_dist + 2*M_PI) < fabs(rought_dist))
484  modulo_dist = rought_dist + 2*M_PI;
485  }
486  //std::cout << "dist " << i << ": " << rought_dist << " modulo: " << modulo_dist << std::endl;
487  dist[i] += weight[j]*vpMath::sqr(modulo_dist);
488  }
489  }
490  // std::cout << "sol " << i << " [" << ok[i] << "] dist: " << dist[i] << " q: " << q_sol[i].t() << std::endl;
491  }
492  //std::cout << "dist: " << dist.t() << std::endl;
493  if (nbsol) {
494  for (unsigned int i=0; i<8; i++) {
495  if (ok[i] == true)
496  if (dist[i] < dist[sol]) sol = i;
497  }
498  // Update the inverse kinematics solution
499  q = q_sol[sol];
500 
501 // std::cout << "Nearest solution (" << sol << ") with distance ("
502 // << dist[sol] << "): " << q_sol[sol].t() << std::endl;
503  }
504  return nbsol;
505 
506 }
507 
558 unsigned int
560 {
564  this->get_wMe(wMe);
565  this->get_eMc(eMc);
566  fMw = fMc * eMc.inverse() * wMe.inverse();
567 
568  return (getInverseKinematicsWrist(fMw,q));
569 }
570 
598 {
600  get_fMc(q, fMc);
601 
602  return fMc;
603 }
604 
626 void
628 {
629 
630  // Compute the direct geometric model: fMe = transformation between
631  // fix and end effector frame.
633 
634  get_fMe(q, fMe);
635 
636  fMc = fMe * this->eMc;
637 
638  return;
639 }
640 
713 void
715 {
716  double q1 = q[0];
717  double q2 = q[1];
718  double q3 = q[2];
719  double q4 = q[3];
720  double q5 = q[4];
721  double q6 = q[5];
722  // We turn off the coupling since the measured positions are joint position
723  // taking into account the coupling factor. The coupling factor is relevant
724  // if positions are motor position.
725  // double q6 = q[5] + c56 * q[4];
726 
727 // std::cout << "q6 motor: " << q[5] << " rad "
728 // << vpMath::deg(q[5]) << " deg" << std::endl;
729 // std::cout << "q6 joint: " << q6 << " rad "
730 // << vpMath::deg(q6) << " deg" << std::endl;
731 
732  double c1 = cos(q1);
733  double s1 = sin(q1);
734  double c2 = cos(q2);
735  double s2 = sin(q2);
736  //double c3 = cos(q3);
737  //double s3 = sin(q3);
738  double c4 = cos(q4);
739  double s4 = sin(q4);
740  double c5 = cos(q5);
741  double s5 = sin(q5);
742  double c6 = cos(q6);
743  double s6 = sin(q6);
744  double c23 = cos(q2+q3);
745  double s23 = sin(q2+q3);
746 
747  fMe[0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
748  fMe[1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
749  fMe[2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
750 
751  fMe[0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
752  fMe[1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
753  fMe[2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
754 
755  fMe[0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
756  fMe[1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
757  fMe[2][2] = -s23*c4*s5+c23*c5;
758 
759  fMe[0][3] = c1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)-s1*s4*s5*d6;
760  fMe[1][3] = s1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)+c1*s4*s5*d6;
761  fMe[2][3] = s23*(a3-c4*s5*d6)+c23*(c5*d6+d4)-a2*s2+d1;
762 
763  // std::cout << "Effector position fMe: " << std::endl << fMe;
764 
765  return;
766 }
809 void
811 {
812  double q1 = q[0];
813  double q2 = q[1];
814  double q3 = q[2];
815  double q4 = q[3];
816  double q5 = q[4];
817  double q6 = q[5];
818  // We turn off the coupling since the measured positions are joint position
819  // taking into account the coupling factor. The coupling factor is relevant
820  // if positions are motor position.
821  // double q6 = q[5] + c56 * q[4];
822 
823 // std::cout << "q6 motor: " << q[5] << " rad "
824 // << vpMath::deg(q[5]) << " deg" << std::endl;
825 // std::cout << "q6 joint: " << q6 << " rad "
826 // << vpMath::deg(q6) << " deg" << std::endl;
827 
828  double c1 = cos(q1);
829  double s1 = sin(q1);
830  double c2 = cos(q2);
831  double s2 = sin(q2);
832  // double c3 = cos(q3);
833  //double s3 = sin(q3);
834  double c4 = cos(q4);
835  double s4 = sin(q4);
836  double c5 = cos(q5);
837  double s5 = sin(q5);
838  double c6 = cos(q6);
839  double s6 = sin(q6);
840  double c23 = cos(q2+q3);
841  double s23 = sin(q2+q3);
842 
843 
844  fMw[0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
845  fMw[1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
846  fMw[2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
847 
848  fMw[0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
849  fMw[1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
850  fMw[2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
851 
852  fMw[0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
853  fMw[1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
854  fMw[2][2] = -s23*c4*s5+c23*c5;
855 
856  fMw[0][3] = c1*(-c23*a3+s23*d4+a1+a2*c2);
857  fMw[1][3] = s1*(-c23*a3+s23*d4+a1+a2*c2);
858  fMw[2][3] = s23*a3+c23*d4-a2*s2+d1;
859 
860  //std::cout << "Wrist position fMw: " << std::endl << fMw;
861 
862  return;
863 }
864 
875 void
877 {
878  // Set the rotation as identity
879  wMe.setIdentity();
880 
881  // Set the translation
882  wMe[2][3] = d6;
883 }
884 
896 void
898 {
899  eMc = this->eMc;
900 }
901 
913 void
915 {
916  cMe = this->eMc.inverse();
917 }
918 
934 void
936 {
937  vpHomogeneousMatrix cMe ;
938  get_cMe(cMe) ;
939 
940  cVe.buildFrom(cMe) ;
941 
942  return;
943 }
944 
967 void
969 {
970  vpMatrix V(6,6);
971  V = 0;
972  // Compute the first and last block of V
974  get_fMw(q, fMw);
975  vpRotationMatrix fRw;
976  fMw.extract(fRw);
977  vpRotationMatrix wRf;
978  wRf = fRw.inverse();
979  for (unsigned int i=0; i<3; i++ ) {
980  for (unsigned int j=0; j<3; j++ ) {
981  V[i][j] = V[i+3][j+3] = wRf[i][j];
982  }
983  }
984  // Compute the second block of V
986  get_wMe(wMe);
988  eMw = wMe.inverse();
990  eMw.extract(etw);
991  vpMatrix block2 = etw.skew()*wRf;
992  for (unsigned int i=0; i<3; i++ ) {
993  for (unsigned int j=0; j<3; j++ ) {
994  V[i][j+3] = block2[i][j];
995  }
996  }
997  // Compute eJe
998  vpMatrix fJw;
999  get_fJw(q, fJw);
1000  eJe = V * fJw;
1001 
1002  return;
1003 }
1004 
1005 
1053 void
1055 {
1056  double q1 = q[0];
1057  double q2 = q[1];
1058  double q3 = q[2];
1059  double q4 = q[3];
1060  double q5 = q[4];
1061 
1062  double c1 = cos(q1);
1063  double s1 = sin(q1);
1064  double c2 = cos(q2);
1065  double s2 = sin(q2);
1066  double c3 = cos(q3);
1067  double s3 = sin(q3);
1068  double c4 = cos(q4);
1069  double s4 = sin(q4);
1070  double c5 = cos(q5);
1071  double s5 = sin(q5);
1072  double c23 = cos(q2+q3);
1073  double s23 = sin(q2+q3);
1074 
1075  vpColVector J1(6);
1076  vpColVector J2(6);
1077  vpColVector J3(6);
1078  vpColVector J4(6);
1079  vpColVector J5(6);
1080  vpColVector J6(6);
1081 
1082  // Jacobian when d6 is set to zero
1083  J1[0] = -s1*(-c23*a3+s23*d4+a1+a2*c2);
1084  J1[1] = c1*(-c23*a3+s23*d4+a1+a2*c2);
1085  J1[2] = 0;
1086  J1[3] = 0;
1087  J1[4] = 0;
1088  J1[5] = 1;
1089 
1090  J2[0] = c1*(s23*a3+c23*d4-a2*s2);
1091  J2[1] = s1*(s23*a3+c23*d4-a2*s2);
1092  J2[2] = c23*a3-s23*d4-a2*c2;
1093  J2[3] = -s1;
1094  J2[4] = c1;
1095  J2[5] = 0;
1096 
1097  J3[0] = c1*(a3*(s2*c3+c2*s3)+(-s2*s3+c2*c3)*d4);
1098  J3[1] = s1*(a3*(s2*c3+c2*s3)+(-s2*s3+c2*c3)*d4);
1099  J3[2] = -a3*(s2*s3-c2*c3)-d4*(s2*c3+c2*s3);
1100  J3[3] = -s1;
1101  J3[4] = c1;
1102  J3[5] = 0;
1103 
1104  J4[0] = 0;
1105  J4[1] = 0;
1106  J4[2] = 0;
1107  J4[3] = c1*s23;
1108  J4[4] = s1*s23;
1109  J4[5] = c23;
1110 
1111  J5[0] = 0;
1112  J5[1] = 0;
1113  J5[2] = 0;
1114  J5[3] = -c23*c1*s4-s1*c4;
1115  J5[4] = c1*c4-c23*s1*s4;
1116  J5[5] = s23*s4;
1117 
1118  J6[0] = 0;
1119  J6[1] = 0;
1120  J6[2] = 0;
1121  J6[3] = (c1*c23*c4-s1*s4)*s5+c1*s23*c5;
1122  J6[4] = (s1*c23*c4+c1*s4)*s5+s1*s23*c5;
1123  J6[5] = -s23*c4*s5+c23*c5;
1124 
1125  fJw.resize(6,6) ;
1126  for (unsigned int i=0;i<6;i++) {
1127  fJw[i][0] = J1[i];
1128  fJw[i][1] = J2[i];
1129  fJw[i][2] = J3[i];
1130  fJw[i][3] = J4[i];
1131  fJw[i][4] = J5[i];
1132  fJw[i][5] = J6[i];
1133  }
1134  return;
1135 }
1159 void
1161 {
1162  vpMatrix V(6,6);
1163  V = 0;
1164  // Set the first and last block to identity
1165  for (unsigned int i=0; i<6; i++ )
1166  V[i][i] = 1;
1167 
1168  // Compute the second block of V
1169  vpHomogeneousMatrix fMw;
1170  get_fMw(q, fMw);
1171  vpRotationMatrix fRw;
1172  fMw.extract(fRw);
1173  vpHomogeneousMatrix wMe;
1174  get_wMe(wMe);
1175  vpHomogeneousMatrix eMw;
1176  eMw = wMe.inverse();
1177  vpTranslationVector etw;
1178  eMw.extract(etw);
1179  vpMatrix block2 = (fRw*etw).skew();
1180  // Set the second block
1181  for (unsigned int i=0; i<3; i++ )
1182  for (unsigned int j=0; j<3; j++ )
1183  V[i][j+3] = block2[i][j];
1184 
1185  // Compute fJe
1186  vpMatrix fJw;
1187  get_fJw(q, fJw);
1188  fJe = V * fJw;
1189 
1190  return;
1191 }
1192 
1193 
1203 {
1204  return joint_min;
1205 }
1206 
1216 {
1217  return joint_max;
1218 }
1219 
1230 double
1232 {
1233  return c56;
1234 }
1235 
1236 
1237 
1247 std::ostream & operator << (std::ostream & os, const vpViper & viper)
1248 {
1249  vpRotationMatrix eRc;
1250  viper.eMc.extract(eRc);
1251  vpRxyzVector rxyz(eRc);
1252 
1253  // Convert joint limits in degrees
1254  vpColVector jmax = viper.joint_max;
1255  vpColVector jmin = viper.joint_min;
1256  jmax.rad2deg();
1257  jmin.rad2deg();
1258 
1259  os
1260  << "Joint Max (deg):" << std::endl
1261  << "\t" << jmax.t() << std::endl
1262 
1263  << "Joint Min (deg): " << std::endl
1264  << "\t" << jmin.t() << std::endl
1265 
1266  << "Coupling 5-6:" << std::endl
1267  << "\t" << viper.c56 << std::endl
1268 
1269  << "eMc: "<< std::endl
1270  << "\tTranslation (m): "
1271  << viper.eMc[0][3] << " "
1272  << viper.eMc[1][3] << " "
1273  << viper.eMc[2][3]
1274  << "\t" << std::endl
1275  << "\tRotation Rxyz (rad) : "
1276  << rxyz[0] << " "
1277  << rxyz[1] << " "
1278  << rxyz[2]
1279  << "\t" << std::endl
1280  << "\tRotation Rxyz (deg) : "
1281  << vpMath::deg(rxyz[0]) << " "
1282  << vpMath::deg(rxyz[1]) << " "
1283  << vpMath::deg(rxyz[2])
1284  << "\t" << std::endl;
1285 
1286  return os;
1287 }
1288 /*
1289  * Local variables:
1290  * c-basic-offset: 2
1291  * End:
1292  */
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
unsigned int getInverseKinematicsWrist(const vpHomogeneousMatrix &fMw, vpColVector &q)
Definition: vpViper.cpp:221
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:968
void setIdentity()
Basic initialisation (identity)
vpColVector getJointMin()
Definition: vpViper.cpp:1202
double a2
for joint 2
Definition: vpViper.h:154
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q)
Definition: vpViper.cpp:559
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:897
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:714
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:1160
vpColVector getJointMax()
Definition: vpViper.cpp:1215
static double deg(double rad)
Definition: vpMath.h:93
void get_wMe(vpHomogeneousMatrix &wMe)
Definition: vpViper.cpp:876
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
void get_fJw(const vpColVector &q, vpMatrix &fJw)
Definition: vpViper.cpp:1054
void get_cMe(vpHomogeneousMatrix &cMe)
Definition: vpViper.cpp:914
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:935
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:176
double getCoupl56()
Definition: vpViper.cpp:1231
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:144
vpHomogeneousMatrix get_fMc(const vpColVector &q)
Definition: vpViper.cpp:597
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:810
double d6
for joint 6
Definition: vpViper.h:157
vpColVector joint_min
Definition: vpViper.h:162