Visual Servoing Platform  version 3.0.0
vpViper.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2015 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), 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  c56 = -341.33 / 9102.22;
79 
80  // Software joint limits in radians
82  joint_min[0] = vpMath::rad(-170);
83  joint_min[1] = vpMath::rad(-190);
84  joint_min[2] = vpMath::rad(-29);
85  joint_min[3] = vpMath::rad(-190);
86  joint_min[4] = vpMath::rad(-120);
87  joint_min[5] = vpMath::rad(-360);
89  joint_max[0] = vpMath::rad(170);
90  joint_max[1] = vpMath::rad(45);
91  joint_max[2] = vpMath::rad(256);
92  joint_max[3] = vpMath::rad(190);
93  joint_max[4] = vpMath::rad(120);
94  joint_max[5] = vpMath::rad(360);
95 
96  // End effector to camera transformation
97  eMc.eye();
98 }
99 
100 
101 
102 
126 {
128  fMc = get_fMc(q);
129 
130  return fMc;
131 }
132 
147 bool
148 vpViper::convertJointPositionInLimits(unsigned int joint, const double &q, double &q_mod, const bool &verbose) const
149 {
150  double eps = 0.01;
151  if (q >= joint_min[joint]-eps && q <= joint_max[joint]+eps ) {
152  q_mod = q;
153  return true;
154  }
155 
156  q_mod = q + 2*M_PI;
157  if (q_mod >= joint_min[joint]-eps && q_mod <= joint_max[joint]+eps ) {
158  return true;
159  }
160 
161  q_mod = q - 2*M_PI;
162  if (q_mod >= joint_min[joint]-eps && q_mod <= joint_max[joint]+eps ) {
163  return true;
164  }
165 
166  if (verbose) {
167  std::cout << "Joint " << joint << " not in limits: "
168  << this->joint_min[joint] << " < " << q << " < " << this->joint_max[joint] << std::endl;
169 
170  }
171 
172  return false;
173 }
174 
227 unsigned int
228 vpViper::getInverseKinematicsWrist(const vpHomogeneousMatrix & fMw, vpColVector & q, const bool &verbose) const
229 {
230  vpColVector q_sol[8];
231 
232  for (unsigned int i=0; i<8; i++)
233  q_sol[i].resize(6);
234 
235  double c1[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
236  double s1[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
237  double c3[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
238  double s3[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
239  double c23[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
240  double s23[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
241  double c4[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
242  double s4[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
243  double c5[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
244  double s5[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
245  double c6[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
246  double s6[8]={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
247 
248  bool ok[8];
249 
250  if (q.getRows() != njoint)
251  q.resize(6);
252 
253  for (unsigned int i=0; i< 8; i++)
254  ok[i] = true;
255 
256  double px = fMw[0][3]; // a*c1
257  double py = fMw[1][3]; // a*s1
258  double pz = fMw[2][3];
259 
260  // Compute q1
261  double a_2 = px*px+py*py;
262  //if (a_2 == 0) {// singularity
263  if (std::fabs(a_2) <= std::numeric_limits<double>::epsilon()) {// singularity
264  c1[0] = cos(q[0]);
265  s1[0] = sin(q[0]);
266  c1[4] = cos(q[0]+M_PI);
267  s1[4] = sin(q[0]+M_PI);
268  }
269  else {
270  double a = sqrt(a_2);
271  c1[0] = px/a;
272  s1[0] = py/a;
273  c1[4] = -px/a;
274  s1[4] = -py/a;
275  }
276 
277  double q1_mod;
278  for(unsigned int i=0;i<8;i+=4) {
279  q_sol[i][0] = atan2(s1[i],c1[i]);
280  if (convertJointPositionInLimits(0, q_sol[i][0], q1_mod, verbose) == true) {
281  q_sol[i][0] = q1_mod;
282  for(unsigned int j=1;j<4;j++) {
283  c1[i+j] = c1[i];
284  s1[i+j] = s1[i];
285  q_sol[i+j][0] = q_sol[i][0];
286  }
287  }
288  else {
289  for(unsigned int j=1;j<4;j++)
290  ok[i+j] = false;
291  }
292  }
293 
294  // Compute q3
295  double K, q3_mod;
296  for(unsigned int i=0; i<8; i+=4) {
297  if(ok[i] == true) {
298  K = (px*px+py*py+pz*pz+a1*a1-a2*a2-a3*a3+d1*d1-d4*d4
299  - 2*(a1*c1[i]*px + a1*s1[i]*py + d1*pz)) / (2*a2);
300  double d4_a3_K = d4*d4+a3*a3-K*K;
301 
302  q_sol[i][2] = atan2(a3, d4) + atan2(K, sqrt(d4_a3_K));
303  q_sol[i+2][2] = atan2(a3, d4) + atan2(K, -sqrt(d4_a3_K));
304 
305  for (unsigned int j=0; j<4; j+=2) {
306  if (d4_a3_K < 0) {
307  for(unsigned int k=0; k<2; k++)
308  ok[i+j+k] = false;
309  }
310  else {
311  if (convertJointPositionInLimits(2, q_sol[i+j][2], q3_mod, verbose) == true) {
312  for(unsigned int k=0; k<2; k++) {
313  q_sol[i+j+k][2] = q3_mod;
314  c3[i+j+k] = cos(q3_mod);
315  s3[i+j+k] = sin(q3_mod);
316  }
317  }
318  else {
319  for(unsigned int k=0; k<2; k++)
320  ok[i+j+k] = false;
321  }
322  }
323  }
324  }
325  }
326  // std::cout << "ok apres q3: ";
327  // for (unsigned int i=0; i< 8; i++)
328  // std::cout << ok[i] << " ";
329  // std::cout << std::endl;
330 
331  // Compute q2
332  double q23[8], q2_mod;
333  for (unsigned int i=0; i<8; i+=2) {
334  if (ok[i] == true) {
335  // Compute q23 = q2+q3
336  c23[i] = (-(a3-a2*c3[i])*(c1[i]*px+s1[i]*py-a1)-(d1-pz)*(d4+a2*s3[i]))
337  / ( (c1[i]*px+s1[i]*py-a1)*(c1[i]*px+s1[i]*py-a1) +(d1-pz)*(d1-pz) );
338  s23[i] = ((d4+a2*s3[i])*(c1[i]*px+s1[i]*py-a1)-(d1-pz)*(a3-a2*c3[i]))
339  / ( (c1[i]*px+s1[i]*py-a1)*(c1[i]*px+s1[i]*py-a1) +(d1-pz)*(d1-pz) );
340  q23[i] = atan2(s23[i],c23[i]);
341  //std::cout << i << " c23 = " << c23[i] << " s23 = " << s23[i] << std::endl;
342  // q2 = q23 - q3
343  q_sol[i][1] = q23[i] - q_sol[i][2];
344 
345  if (convertJointPositionInLimits(1, q_sol[i][1], q2_mod, verbose) == true) {
346  for(unsigned int j=0; j<2; j++) {
347  q_sol[i+j][1] = q2_mod;
348  c23[i+j] = c23[i];
349  s23[i+j] = s23[i];
350  }
351  }
352  else {
353  for(unsigned int j=0; j<2; j++)
354  ok[i+j] = false;
355  }
356  }
357  }
358  // std::cout << "ok apres q2: ";
359  // for (unsigned int i=0; i< 8; i++)
360  // std::cout << ok[i] << " ";
361  // std::cout << std::endl;
362 
363  // Compute q4 as long as s5 != 0
364  double r13 = fMw[0][2];
365  double r23 = fMw[1][2];
366  double r33 = fMw[2][2];
367  double s4s5, c4s5, q4_mod, q5_mod;
368  for (unsigned int i=0; i<8; i+=2) {
369  if (ok[i] == true) {
370  s4s5 = -s1[i]*r13+c1[i]*r23;
371  c4s5 = c1[i]*c23[i]*r13+s1[i]*c23[i]*r23-s23[i]*r33;
372  if (fabs(s4s5) < vpMath::rad(0.5) && fabs(c4s5) < vpMath::rad(0.5)) {
373  // s5 = 0
374  c5[i] = c1[i]*s23[i]*r13+s1[i]*s23[i]*r23+c23[i]*r33;
375  //std::cout << "Singularity: s5 near 0: ";
376  if (c5[i] > 0.)
377  q_sol[i][4] = 0.0;
378  else
379  q_sol[i][4] = M_PI;
380 
381  if (convertJointPositionInLimits(4, q_sol[i][4], q5_mod, verbose) == true) {
382  for(unsigned int j=0; j<2; j++) {
383  q_sol[i+j][3] = q[3]; // keep current q4
384  q_sol[i+j][4] = q5_mod;
385  c4[i] = cos(q_sol[i+j][3]);
386  s4[i] = sin(q_sol[i+j][3]);
387  }
388  }
389  else {
390  for(unsigned int j=0; j<2; j++)
391  ok[i+j] = false;
392  }
393  }
394  else {
395  // s5 != 0
396  //if (c4s5 == 0) {
397  if (std::fabs(c4s5) <= std::numeric_limits<double>::epsilon()) {
398  // c4 = 0
399  // vpTRACE("c4 = 0");
400  // q_sol[i][3] = q[3]; // keep current position
401  q_sol[i][3] = atan2(s4s5, c4s5);
402  }
403  else {
404  q_sol[i][3] = atan2(s4s5, c4s5);
405  }
406  if (convertJointPositionInLimits(3, q_sol[i][3], q4_mod, verbose) == true) {
407  q_sol[i][3] = q4_mod;
408  c4[i] = cos(q4_mod);
409  s4[i] = sin(q4_mod);
410  }
411  else {
412  ok[i] = false;
413  }
414  if (q_sol[i][3] > 0.)
415  q_sol[i+1][3] = q_sol[i][3] + M_PI;
416  else
417  q_sol[i+1][3] = q_sol[i][3] - M_PI;
418  if (convertJointPositionInLimits(3, q_sol[i+1][3], q4_mod, verbose) == true) {
419  q_sol[i+1][3] = q4_mod;
420  c4[i+1] = cos(q4_mod);
421  s4[i+1] = sin(q4_mod);
422  }
423  else {
424  ok[i+1] = false;
425  }
426 
427  // Compute q5
428  for (unsigned int j=0; j<2; j++) {
429  if (ok[i+j] == true) {
430  c5[i+j] = c1[i+j]*s23[i+j]*r13+s1[i+j]*s23[i+j]*r23+c23[i+j]*r33;
431  s5[i+j] = (c1[i+j]*c23[i+j]*c4[i+j]-s1[i+j]*s4[i+j])*r13
432  +(s1[i+j]*c23[i+j]*c4[i+j]+c1[i+j]*s4[i+j])*r23-s23[i+j]*c4[i+j]*r33;
433 
434  q_sol[i+j][4] = atan2(s5[i+j], c5[i+j]);
435  if (convertJointPositionInLimits(4, q_sol[i+j][4], q5_mod, verbose) == true) {
436  q_sol[i+j][4] = q5_mod;
437  }
438  else {
439 
440  ok[i+j] = false;
441  }
442  }
443  }
444  }
445  }
446  }
447 
448  // Compute q6
449  // 4 solutions for q6 and 4 more solutions by flipping the wrist (see below)
450  double r12 = fMw[0][1];
451  double r22 = fMw[1][1];
452  double r32 = fMw[2][1];
453  double q6_mod;
454  for (unsigned int i=0; i<8; i++) {
455  c6[i] = -(c1[i]*c23[i]*s4[i]+s1[i]*c4[i])*r12
456  +(c1[i]*c4[i]-s1[i]*c23[i]*s4[i])*r22+s23[i]*s4[i]*r32;
457  s6[i] = -(c1[i]*c23[i]*c4[i]*c5[i]-c1[i]*s23[i]*s5[i]
458  -s1[i]*s4[i]*c5[i])*r12
459  -(s1[i]*c23[i]*c4[i]*c5[i]-s1[i]*s23[i]*s5[i]+c1[i]*s4[i]*c5[i])*r22
460  +(c23[i]*s5[i]+s23[i]*c4[i]*c5[i])*r32;
461 
462  q_sol[i][5] = atan2(s6[i], c6[i]);
463  if (convertJointPositionInLimits(5, q_sol[i][5], q6_mod, verbose) == true) {
464  q_sol[i][5] = q6_mod;
465  }
466  else {
467  ok[i] = false;
468  }
469  }
470 
471  // Select the best config in terms of distance from the current position
472  unsigned int nbsol = 0;
473  unsigned int sol = 0;
474  vpColVector dist(8);
475  for (unsigned int i=0; i<8; i++) {
476  if (ok[i] == true) {
477  nbsol ++;
478  sol = i;
479  // dist[i] = vpColVector::distance(q, q_sol[i]);
480  vpColVector weight(6);
481  weight = 1;
482  weight[0] = 8;
483  weight[1] = weight[2] = 4;
484  dist[i] = 0;
485  for (unsigned int j=0; j< 6; j++) {
486  double rought_dist = q[j]- q_sol[i][j];
487  double modulo_dist = rought_dist;
488  if (rought_dist > 0) {
489  if (fabs(rought_dist - 2*M_PI) < fabs(rought_dist))
490  modulo_dist = rought_dist - 2*M_PI;
491  }
492  else {
493  if (fabs(rought_dist + 2*M_PI) < fabs(rought_dist))
494  modulo_dist = rought_dist + 2*M_PI;
495  }
496  //std::cout << "dist " << i << ": " << rought_dist << " modulo: " << modulo_dist << std::endl;
497  dist[i] += weight[j]*vpMath::sqr(modulo_dist);
498  }
499  }
500  // std::cout << "sol " << i << " [" << ok[i] << "] dist: " << dist[i] << " q: " << q_sol[i].t() << std::endl;
501  }
502  //std::cout << "dist: " << dist.t() << std::endl;
503  if (nbsol) {
504  for (unsigned int i=0; i<8; i++) {
505  if (ok[i] == true)
506  if (dist[i] < dist[sol]) sol = i;
507  }
508  // Update the inverse kinematics solution
509  q = q_sol[sol];
510 
511  // std::cout << "Nearest solution (" << sol << ") with distance ("
512  // << dist[sol] << "): " << q_sol[sol].t() << std::endl;
513  }
514  return nbsol;
515 
516 }
517 
572 unsigned int
573 vpViper::getInverseKinematics(const vpHomogeneousMatrix & fMc, vpColVector & q, const bool &verbose) const
574 {
577  vpHomogeneousMatrix eMc_;
578  this->get_wMe(wMe);
579  this->get_eMc(eMc_);
580  fMw = fMc * eMc_.inverse() * wMe.inverse();
581 
582  return (getInverseKinematicsWrist(fMw, q, verbose));
583 }
584 
611 vpViper::get_fMc (const vpColVector & q) const
612 {
614  get_fMc(q, fMc);
615 
616  return fMc;
617 }
618 
640 void
642 {
643 
644  // Compute the direct geometric model: fMe = transformation between
645  // fix and end effector frame.
647 
648  get_fMe(q, fMe);
649 
650  fMc = fMe * this->eMc;
651 
652  return;
653 }
654 
727 void
729 {
730  double q1 = q[0];
731  double q2 = q[1];
732  double q3 = q[2];
733  double q4 = q[3];
734  double q5 = q[4];
735  double q6 = q[5];
736  // We turn off the coupling since the measured positions are joint position
737  // taking into account the coupling factor. The coupling factor is relevant
738  // if positions are motor position.
739  // double q6 = q[5] + c56 * q[4];
740 
741 // std::cout << "q6 motor: " << q[5] << " rad "
742 // << vpMath::deg(q[5]) << " deg" << std::endl;
743 // std::cout << "q6 joint: " << q6 << " rad "
744 // << vpMath::deg(q6) << " deg" << std::endl;
745 
746  double c1 = cos(q1);
747  double s1 = sin(q1);
748  double c2 = cos(q2);
749  double s2 = sin(q2);
750  //double c3 = cos(q3);
751  //double s3 = sin(q3);
752  double c4 = cos(q4);
753  double s4 = sin(q4);
754  double c5 = cos(q5);
755  double s5 = sin(q5);
756  double c6 = cos(q6);
757  double s6 = sin(q6);
758  double c23 = cos(q2+q3);
759  double s23 = sin(q2+q3);
760 
761  fMe[0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
762  fMe[1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
763  fMe[2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
764 
765  fMe[0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
766  fMe[1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
767  fMe[2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
768 
769  fMe[0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
770  fMe[1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
771  fMe[2][2] = -s23*c4*s5+c23*c5;
772 
773  fMe[0][3] = c1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)-s1*s4*s5*d6;
774  fMe[1][3] = s1*(c23*(c4*s5*d6-a3)+s23*(c5*d6+d4)+a1+a2*c2)+c1*s4*s5*d6;
775  fMe[2][3] = s23*(a3-c4*s5*d6)+c23*(c5*d6+d4)-a2*s2+d1;
776 
777  // std::cout << "Effector position fMe: " << std::endl << fMe;
778 
779  return;
780 }
823 void
825 {
826  double q1 = q[0];
827  double q2 = q[1];
828  double q3 = q[2];
829  double q4 = q[3];
830  double q5 = q[4];
831  double q6 = q[5];
832  // We turn off the coupling since the measured positions are joint position
833  // taking into account the coupling factor. The coupling factor is relevant
834  // if positions are motor position.
835  // double q6 = q[5] + c56 * q[4];
836 
837 // std::cout << "q6 motor: " << q[5] << " rad "
838 // << vpMath::deg(q[5]) << " deg" << std::endl;
839 // std::cout << "q6 joint: " << q6 << " rad "
840 // << vpMath::deg(q6) << " deg" << std::endl;
841 
842  double c1 = cos(q1);
843  double s1 = sin(q1);
844  double c2 = cos(q2);
845  double s2 = sin(q2);
846  // double c3 = cos(q3);
847  //double s3 = sin(q3);
848  double c4 = cos(q4);
849  double s4 = sin(q4);
850  double c5 = cos(q5);
851  double s5 = sin(q5);
852  double c6 = cos(q6);
853  double s6 = sin(q6);
854  double c23 = cos(q2+q3);
855  double s23 = sin(q2+q3);
856 
857  fMw[0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
858  fMw[1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
859  fMw[2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
860 
861  fMw[0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
862  fMw[1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
863  fMw[2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
864 
865  fMw[0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
866  fMw[1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
867  fMw[2][2] = -s23*c4*s5+c23*c5;
868 
869  fMw[0][3] = c1*(-c23*a3+s23*d4+a1+a2*c2);
870  fMw[1][3] = s1*(-c23*a3+s23*d4+a1+a2*c2);
871  fMw[2][3] = s23*a3+c23*d4-a2*s2+d1;
872 
873  //std::cout << "Wrist position fMw: " << std::endl << fMw;
874 
875  return;
876 }
877 
888 void
890 {
891  // Set the rotation as identity
892  wMe.eye();
893 
894  // Set the translation
895  wMe[2][3] = d6;
896 }
897 
909 void
911 {
912  eMc_ = this->eMc;
913 }
914 
926 void
928 {
929  cMe = this->eMc.inverse();
930 }
931 
947 void
949 {
950  vpHomogeneousMatrix cMe ;
951  get_cMe(cMe) ;
952 
953  cVe.buildFrom(cMe) ;
954 
955  return;
956 }
957 
980 void
981 vpViper::get_eJe(const vpColVector &q, vpMatrix &eJe) const
982 {
983  vpMatrix V(6,6);
984  V = 0;
985  // Compute the first and last block of V
987  get_fMw(q, fMw);
988  vpRotationMatrix fRw;
989  fMw.extract(fRw);
990  vpRotationMatrix wRf;
991  wRf = fRw.inverse();
992  for (unsigned int i=0; i<3; i++ ) {
993  for (unsigned int j=0; j<3; j++ ) {
994  V[i][j] = V[i+3][j+3] = wRf[i][j];
995  }
996  }
997  // Compute the second block of V
999  get_wMe(wMe);
1000  vpHomogeneousMatrix eMw;
1001  eMw = wMe.inverse();
1002  vpTranslationVector etw;
1003  eMw.extract(etw);
1004  vpMatrix block2 = etw.skew()*wRf;
1005  for (unsigned int i=0; i<3; i++ ) {
1006  for (unsigned int j=0; j<3; j++ ) {
1007  V[i][j+3] = block2[i][j];
1008  }
1009  }
1010  // Compute eJe
1011  vpMatrix fJw;
1012  get_fJw(q, fJw);
1013  eJe = V * fJw;
1014 
1015  return;
1016 }
1017 
1018 
1066 void
1068 {
1069  double q1 = q[0];
1070  double q2 = q[1];
1071  double q3 = q[2];
1072  double q4 = q[3];
1073  double q5 = q[4];
1074 
1075  double c1 = cos(q1);
1076  double s1 = sin(q1);
1077  double c2 = cos(q2);
1078  double s2 = sin(q2);
1079  double c3 = cos(q3);
1080  double s3 = sin(q3);
1081  double c4 = cos(q4);
1082  double s4 = sin(q4);
1083  double c5 = cos(q5);
1084  double s5 = sin(q5);
1085  double c23 = cos(q2+q3);
1086  double s23 = sin(q2+q3);
1087 
1088  vpColVector J1(6);
1089  vpColVector J2(6);
1090  vpColVector J3(6);
1091  vpColVector J4(6);
1092  vpColVector J5(6);
1093  vpColVector J6(6);
1094 
1095  // Jacobian when d6 is set to zero
1096  J1[0] = -s1*(-c23*a3+s23*d4+a1+a2*c2);
1097  J1[1] = c1*(-c23*a3+s23*d4+a1+a2*c2);
1098  J1[2] = 0;
1099  J1[3] = 0;
1100  J1[4] = 0;
1101  J1[5] = 1;
1102 
1103  J2[0] = c1*(s23*a3+c23*d4-a2*s2);
1104  J2[1] = s1*(s23*a3+c23*d4-a2*s2);
1105  J2[2] = c23*a3-s23*d4-a2*c2;
1106  J2[3] = -s1;
1107  J2[4] = c1;
1108  J2[5] = 0;
1109 
1110  J3[0] = c1*(a3*(s2*c3+c2*s3)+(-s2*s3+c2*c3)*d4);
1111  J3[1] = s1*(a3*(s2*c3+c2*s3)+(-s2*s3+c2*c3)*d4);
1112  J3[2] = -a3*(s2*s3-c2*c3)-d4*(s2*c3+c2*s3);
1113  J3[3] = -s1;
1114  J3[4] = c1;
1115  J3[5] = 0;
1116 
1117  J4[0] = 0;
1118  J4[1] = 0;
1119  J4[2] = 0;
1120  J4[3] = c1*s23;
1121  J4[4] = s1*s23;
1122  J4[5] = c23;
1123 
1124  J5[0] = 0;
1125  J5[1] = 0;
1126  J5[2] = 0;
1127  J5[3] = -c23*c1*s4-s1*c4;
1128  J5[4] = c1*c4-c23*s1*s4;
1129  J5[5] = s23*s4;
1130 
1131  J6[0] = 0;
1132  J6[1] = 0;
1133  J6[2] = 0;
1134  J6[3] = (c1*c23*c4-s1*s4)*s5+c1*s23*c5;
1135  J6[4] = (s1*c23*c4+c1*s4)*s5+s1*s23*c5;
1136  J6[5] = -s23*c4*s5+c23*c5;
1137 
1138  fJw.resize(6,6) ;
1139  for (unsigned int i=0;i<6;i++) {
1140  fJw[i][0] = J1[i];
1141  fJw[i][1] = J2[i];
1142  fJw[i][2] = J3[i];
1143  fJw[i][3] = J4[i];
1144  fJw[i][4] = J5[i];
1145  fJw[i][5] = J6[i];
1146  }
1147  return;
1148 }
1172 void
1174 {
1175  vpMatrix V(6,6);
1176  V = 0;
1177  // Set the first and last block to identity
1178  for (unsigned int i=0; i<6; i++ )
1179  V[i][i] = 1;
1180 
1181  // Compute the second block of V
1182  vpHomogeneousMatrix fMw;
1183  get_fMw(q, fMw);
1184  vpRotationMatrix fRw;
1185  fMw.extract(fRw);
1186  vpHomogeneousMatrix wMe;
1187  get_wMe(wMe);
1188  vpHomogeneousMatrix eMw;
1189  eMw = wMe.inverse();
1190  vpTranslationVector etw;
1191  eMw.extract(etw);
1192  vpMatrix block2 = (fRw*etw).skew();
1193  // Set the second block
1194  for (unsigned int i=0; i<3; i++ )
1195  for (unsigned int j=0; j<3; j++ )
1196  V[i][j+3] = block2[i][j];
1197 
1198  // Compute fJe
1199  vpMatrix fJw;
1200  get_fJw(q, fJw);
1201  fJe = V * fJw;
1202 
1203  return;
1204 }
1205 
1206 
1216 {
1217  return joint_min;
1218 }
1219 
1229 {
1230  return joint_max;
1231 }
1232 
1243 double
1245 {
1246  return c56;
1247 }
1248 
1257 void
1259 {
1260  this->eMc = eMc_;
1261  this->eMc.extract(etc);
1262  vpRotationMatrix R(this->eMc);
1263  this->erc.buildFrom(R);
1264 }
1265 
1276 void
1278 {
1279  this->etc = etc_;
1280  this->erc = erc_;
1281  vpRotationMatrix eRc(erc);
1282  this->eMc.buildFrom(etc,eRc);
1283 }
1284 
1294 VISP_EXPORT std::ostream & operator << (std::ostream & os, const vpViper & viper)
1295 {
1296  vpRotationMatrix eRc;
1297  viper.eMc.extract(eRc);
1298  vpRxyzVector rxyz(eRc);
1299 
1300  // Convert joint limits in degrees
1301  vpColVector jmax = viper.joint_max;
1302  vpColVector jmin = viper.joint_min;
1303  jmax.rad2deg();
1304  jmin.rad2deg();
1305 
1306  os
1307  << "Joint Max (deg):" << std::endl
1308  << "\t" << jmax.t() << std::endl
1309 
1310  << "Joint Min (deg): " << std::endl
1311  << "\t" << jmin.t() << std::endl
1312 
1313  << "Coupling 5-6:" << std::endl
1314  << "\t" << viper.c56 << std::endl
1315 
1316  << "eMc: "<< std::endl
1317  << "\tTranslation (m): "
1318  << viper.eMc[0][3] << " "
1319  << viper.eMc[1][3] << " "
1320  << viper.eMc[2][3]
1321  << "\t" << std::endl
1322  << "\tRotation Rxyz (rad) : "
1323  << rxyz[0] << " "
1324  << rxyz[1] << " "
1325  << rxyz[2]
1326  << "\t" << std::endl
1327  << "\tRotation Rxyz (deg) : "
1328  << vpMath::deg(rxyz[0]) << " "
1329  << vpMath::deg(rxyz[1]) << " "
1330  << vpMath::deg(rxyz[2])
1331  << "\t" << std::endl;
1332 
1333  return os;
1334 }
void get_cVe(vpVelocityTwistMatrix &cVe) const
Definition: vpViper.cpp:948
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:92
vpRxyzVector buildFrom(const vpRotationMatrix &R)
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpViper.cpp:981
void get_fMw(const vpColVector &q, vpHomogeneousMatrix &fMw) const
Definition: vpViper.cpp:824
double a3
for joint 3
Definition: vpViper.h:153
vpHomogeneousMatrix eMc
End effector to camera transformation.
Definition: vpViper.h:145
vpRotationMatrix inverse() const
Modelisation of the ADEPT Viper robot.
Definition: vpViper.h:107
double getCoupl56() const
Definition: vpViper.cpp:1244
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:228
void get_wMe(vpHomogeneousMatrix &wMe) const
Definition: vpViper.cpp:889
Implementation of an homogeneous matrix and operations on such kind of matrices.
void get_eMc(vpHomogeneousMatrix &eMc) const
Definition: vpViper.cpp:910
vpRxyzVector erc
Definition: vpViper.h:148
double a2
for joint 2
Definition: vpViper.h:152
Implementation of a rotation matrix and operations on such kind of matrices.
double d1
for joint 1
Definition: vpViper.h:151
double c56
Mechanical coupling between joint 5 and joint 6.
Definition: vpViper.h:156
double a1
Definition: vpViper.h:151
vpTranslationVector etc
Definition: vpViper.h:147
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
Definition: vpViper.cpp:1258
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:159
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:611
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
Definition: vpViper.cpp:728
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:1067
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:573
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:1173
vpColVector getJointMin() const
Definition: vpViper.cpp:1215
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:927
static double deg(double rad)
Definition: vpMath.h:97
vpColVector getJointMax() const
Definition: vpViper.cpp:1228
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:154
vpViper()
Definition: vpViper.cpp:66
vpHomogeneousMatrix getForwardKinematics(const vpColVector &q) const
Definition: vpViper.cpp:125
Class that consider the case of a translation vector.
void rad2deg()
Definition: vpColVector.h:202
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:142
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:217
double d6
for joint 6
Definition: vpViper.h:155
vpColVector joint_min
Definition: vpViper.h:160