Visual Servoing Platform  version 3.6.1 under development (2024-11-14)
vpViper.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Interface for a generic ADEPT Viper (either 650 or 850) robot.
33  *
34 *****************************************************************************/
35 
44 #include <cmath> // std::fabs
45 #include <limits> // numeric_limits
46 #include <visp3/core/vpCameraParameters.h>
47 #include <visp3/core/vpDebug.h>
48 #include <visp3/core/vpRotationMatrix.h>
49 #include <visp3/core/vpRxyzVector.h>
50 #include <visp3/core/vpTranslationVector.h>
51 #include <visp3/core/vpVelocityTwistMatrix.h>
52 #include <visp3/robot/vpRobotException.h>
53 #include <visp3/robot/vpViper.h>
54 
55 BEGIN_VISP_NAMESPACE
56 const unsigned int vpViper::njoint = 6;
57 
64  : eMc(), etc(), erc(), a1(0), d1(0), a2(), a3(), d4(0), d6(0), d7(0), c56(0), joint_max(), joint_min()
65 {
66  // Default values are initialized
67 
68  // Denavit-Hartenberg parameters
69  a1 = 0.075;
70  a2 = 0.365;
71  a3 = 0.090;
72  d1 = 0.335;
73  d4 = 0.405;
74  d6 = 0.080;
75  d7 = 0.0666;
76  c56 = -341.33 / 9102.22;
77 
78  // Software joint limits in radians
80  joint_min[0] = vpMath::rad(-170);
81  joint_min[1] = vpMath::rad(-190);
82  joint_min[2] = vpMath::rad(-29);
83  joint_min[3] = vpMath::rad(-190);
84  joint_min[4] = vpMath::rad(-120);
85  joint_min[5] = vpMath::rad(-360);
87  joint_max[0] = vpMath::rad(170);
88  joint_max[1] = vpMath::rad(45);
89  joint_max[2] = vpMath::rad(256);
90  joint_max[3] = vpMath::rad(190);
91  joint_max[4] = vpMath::rad(120);
92  joint_max[5] = vpMath::rad(360);
93 
94  // End effector to camera transformation
95  eMc.eye();
96 }
97 
120 {
122  fMc = get_fMc(q);
123 
124  return fMc;
125 }
126 
141 bool vpViper::convertJointPositionInLimits(unsigned int joint, const double &q, double &q_mod,
142  const bool &verbose) const
143 {
144  double eps = 0.01;
145  if (q >= joint_min[joint] - eps && q <= joint_max[joint] + eps) {
146  q_mod = q;
147  return true;
148  }
149 
150  q_mod = q + 2 * M_PI;
151  if (q_mod >= joint_min[joint] - eps && q_mod <= joint_max[joint] + eps) {
152  return true;
153  }
154 
155  q_mod = q - 2 * M_PI;
156  if (q_mod >= joint_min[joint] - eps && q_mod <= joint_max[joint] + eps) {
157  return true;
158  }
159 
160  if (verbose) {
161  std::cout << "Joint " << joint << " not in limits: " << this->joint_min[joint] << " < " << q << " < "
162  << this->joint_max[joint] << std::endl;
163  }
164 
165  return false;
166 }
167 
221  const bool &verbose) const
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, verbose) == 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  // Compute q3
288  double K, q3_mod;
289  for (unsigned int i = 0; i < 8; i += 4) {
290  if (ok[i] == true) {
291  K = (px * px + py * py + pz * pz + a1 * a1 - a2 * a2 - a3 * a3 + d1 * d1 - d4 * d4 -
292  2 * (a1 * c1[i] * px + a1 * s1[i] * py + d1 * pz)) /
293  (2 * a2);
294  double d4_a3_K = d4 * d4 + a3 * a3 - K * K;
295 
296  q_sol[i][2] = atan2(a3, d4) + atan2(K, sqrt(d4_a3_K));
297  q_sol[i + 2][2] = atan2(a3, d4) + atan2(K, -sqrt(d4_a3_K));
298 
299  for (unsigned int j = 0; j < 4; j += 2) {
300  if (d4_a3_K < 0) {
301  for (unsigned int k = 0; k < 2; k++)
302  ok[i + j + k] = false;
303  }
304  else {
305  if (convertJointPositionInLimits(2, q_sol[i + j][2], q3_mod, verbose) == true) {
306  for (unsigned int k = 0; k < 2; k++) {
307  q_sol[i + j + k][2] = q3_mod;
308  c3[i + j + k] = cos(q3_mod);
309  s3[i + j + k] = sin(q3_mod);
310  }
311  }
312  else {
313  for (unsigned int k = 0; k < 2; k++)
314  ok[i + j + k] = false;
315  }
316  }
317  }
318  }
319  }
320  // std::cout << "ok apres q3: ";
321  // for (unsigned int i=0; i< 8; i++)
322  // std::cout << ok[i] << " ";
323  // std::cout << std::endl;
324 
325  // Compute q2
326  double q23[8], q2_mod;
327  for (unsigned int i = 0; i < 8; i += 2) {
328  if (ok[i] == true) {
329  // Compute q23 = q2+q3
330  c23[i] = (-(a3 - a2 * c3[i]) * (c1[i] * px + s1[i] * py - a1) - (d1 - pz) * (d4 + a2 * s3[i])) /
331  ((c1[i] * px + s1[i] * py - a1) * (c1[i] * px + s1[i] * py - a1) + (d1 - pz) * (d1 - pz));
332  s23[i] = ((d4 + a2 * s3[i]) * (c1[i] * px + s1[i] * py - a1) - (d1 - pz) * (a3 - a2 * c3[i])) /
333  ((c1[i] * px + s1[i] * py - a1) * (c1[i] * px + s1[i] * py - a1) + (d1 - pz) * (d1 - pz));
334  q23[i] = atan2(s23[i], c23[i]);
335  // std::cout << i << " c23 = " << c23[i] << " s23 = " << s23[i] <<
336  // std::endl;
337  // q2 = q23 - q3
338  q_sol[i][1] = q23[i] - q_sol[i][2];
339 
340  if (convertJointPositionInLimits(1, q_sol[i][1], q2_mod, verbose) == true) {
341  for (unsigned int j = 0; j < 2; j++) {
342  q_sol[i + j][1] = q2_mod;
343  c23[i + j] = c23[i];
344  s23[i + j] = s23[i];
345  }
346  }
347  else {
348  for (unsigned int j = 0; j < 2; j++)
349  ok[i + j] = false;
350  }
351  }
352  }
353  // std::cout << "ok apres q2: ";
354  // for (unsigned int i=0; i< 8; i++)
355  // std::cout << ok[i] << " ";
356  // std::cout << std::endl;
357 
358  // Compute q4 as long as s5 != 0
359  double r13 = fMw[0][2];
360  double r23 = fMw[1][2];
361  double r33 = fMw[2][2];
362  double s4s5, c4s5, q4_mod, q5_mod;
363  for (unsigned int i = 0; i < 8; i += 2) {
364  if (ok[i] == true) {
365  s4s5 = -s1[i] * r13 + c1[i] * r23;
366  c4s5 = c1[i] * c23[i] * r13 + s1[i] * c23[i] * r23 - s23[i] * r33;
367  if (fabs(s4s5) < vpMath::rad(0.5) && fabs(c4s5) < vpMath::rad(0.5)) {
368  // s5 = 0
369  c5[i] = c1[i] * s23[i] * r13 + s1[i] * s23[i] * r23 + c23[i] * r33;
370  // std::cout << "Singularity: s5 near 0: ";
371  if (c5[i] > 0.)
372  q_sol[i][4] = 0.0;
373  else
374  q_sol[i][4] = M_PI;
375 
376  if (convertJointPositionInLimits(4, q_sol[i][4], q5_mod, verbose) == true) {
377  for (unsigned int j = 0; j < 2; j++) {
378  q_sol[i + j][3] = q[3]; // keep current q4
379  q_sol[i + j][4] = q5_mod;
380  c4[i] = cos(q_sol[i + j][3]);
381  s4[i] = sin(q_sol[i + j][3]);
382  }
383  }
384  else {
385  for (unsigned int j = 0; j < 2; j++)
386  ok[i + j] = false;
387  }
388  }
389  else {
390 // s5 != 0
391 #if 0 // Modified 2016/03/10 since if and else are the same
392  // if (c4s5 == 0) {
393  if (std::fabs(c4s5) <= std::numeric_limits<double>::epsilon()) {
394  // c4 = 0
395  // vpTRACE("c4 = 0");
396  // q_sol[i][3] = q[3]; // keep current position
397  q_sol[i][3] = atan2(s4s5, c4s5);
398  }
399  else {
400  q_sol[i][3] = atan2(s4s5, c4s5);
401  }
402 #else
403  q_sol[i][3] = atan2(s4s5, c4s5);
404 #endif
405  if (convertJointPositionInLimits(3, q_sol[i][3], q4_mod, verbose) == true) {
406  q_sol[i][3] = q4_mod;
407  c4[i] = cos(q4_mod);
408  s4[i] = sin(q4_mod);
409  }
410  else {
411  ok[i] = false;
412  }
413  if (q_sol[i][3] > 0.)
414  q_sol[i + 1][3] = q_sol[i][3] + M_PI;
415  else
416  q_sol[i + 1][3] = q_sol[i][3] - M_PI;
417  if (convertJointPositionInLimits(3, q_sol[i + 1][3], q4_mod, verbose) == true) {
418  q_sol[i + 1][3] = q4_mod;
419  c4[i + 1] = cos(q4_mod);
420  s4[i + 1] = sin(q4_mod);
421  }
422  else {
423  ok[i + 1] = false;
424  }
425 
426  // Compute q5
427  for (unsigned int j = 0; j < 2; j++) {
428  if (ok[i + j] == true) {
429  c5[i + j] = c1[i + j] * s23[i + j] * r13 + s1[i + j] * s23[i + j] * r23 + c23[i + j] * r33;
430  s5[i + j] = (c1[i + j] * c23[i + j] * c4[i + j] - s1[i + j] * s4[i + j]) * r13 +
431  (s1[i + j] * c23[i + j] * c4[i + j] + c1[i + j] * s4[i + j]) * r23 -
432  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 + (c1[i] * c4[i] - s1[i] * c23[i] * s4[i]) * r22 +
456  s23[i] * s4[i] * r32;
457  s6[i] = -(c1[i] * c23[i] * c4[i] * c5[i] - c1[i] * s23[i] * s5[i] - s1[i] * s4[i] * c5[i]) * r12 -
458  (s1[i] * c23[i] * c4[i] * c5[i] - s1[i] * s23[i] * s5[i] + c1[i] * s4[i] * c5[i]) * r22 +
459  (c23[i] * s5[i] + s23[i] * c4[i] * c5[i]) * r32;
460 
461  q_sol[i][5] = atan2(s6[i], c6[i]);
462  if (convertJointPositionInLimits(5, q_sol[i][5], q6_mod, verbose) == true) {
463  q_sol[i][5] = q6_mod;
464  }
465  else {
466  ok[i] = false;
467  }
468  }
469 
470  // Select the best config in terms of distance from the current position
471  unsigned int nbsol = 0;
472  unsigned int sol = 0;
473  vpColVector dist(8);
474  for (unsigned int i = 0; i < 8; i++) {
475  if (ok[i] == true) {
476  nbsol++;
477  sol = i;
478  vpColVector weight(6);
479  weight = 1;
480  weight[0] = 8;
481  weight[1] = weight[2] = 4;
482  dist[i] = 0;
483  for (unsigned int j = 0; j < 6; j++) {
484  double rought_dist = q[j] - q_sol[i][j];
485  double modulo_dist = rought_dist;
486  if (rought_dist > 0) {
487  if (fabs(rought_dist - 2 * M_PI) < fabs(rought_dist))
488  modulo_dist = rought_dist - 2 * M_PI;
489  }
490  else {
491  if (fabs(rought_dist + 2 * M_PI) < fabs(rought_dist))
492  modulo_dist = rought_dist + 2 * M_PI;
493  }
494 
495  dist[i] += weight[j] * vpMath::sqr(modulo_dist);
496  }
497  }
498 
499  }
500  // std::cout << "dist: " << dist.t() << std::endl;
501  if (nbsol) {
502  for (unsigned int i = 0; i < 8; i++) {
503  if (ok[i] == true)
504  if (dist[i] < dist[sol])
505  sol = i;
506  }
507  // Update the inverse kinematics solution
508  q = q_sol[sol];
509 
510  }
511  return nbsol;
512 }
513 
568 unsigned int vpViper::getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose) const
569 {
572  vpHomogeneousMatrix eMc_;
573  this->get_wMe(wMe);
574  this->get_eMc(eMc_);
575  fMw = fMc * eMc_.inverse() * wMe.inverse();
576 
577  return (getInverseKinematicsWrist(fMw, q, verbose));
578 }
579 
606 {
608  get_fMc(q, fMc);
609 
610  return fMc;
611 }
612 
635 {
636 
637  // Compute the direct geometric model: fMe = transformation between
638  // fix and end effector frame.
640 
641  get_fMe(q, fMe);
642 
643  fMc = fMe * this->eMc;
644 
645  return;
646 }
647 
725 {
726  double q1 = q[0];
727  double q2 = q[1];
728  double q3 = q[2];
729  double q4 = q[3];
730  double q5 = q[4];
731  double q6 = q[5];
732  // We turn off the coupling since the measured positions are joint position
733  // taking into account the coupling factor. The coupling factor is relevant
734  // if positions are motor position.
735  // double q6 = q[5] + c56 * q[4];
736 
737  double c1 = cos(q1);
738  double s1 = sin(q1);
739  double c2 = cos(q2);
740  double s2 = sin(q2);
741  // double c3 = cos(q3);
742  // double s3 = sin(q3);
743  double c4 = cos(q4);
744  double s4 = sin(q4);
745  double c5 = cos(q5);
746  double s5 = sin(q5);
747  double c6 = cos(q6);
748  double s6 = sin(q6);
749  double c23 = cos(q2 + q3);
750  double s23 = sin(q2 + q3);
751 
752  fMe[0][0] = c1 * (c23 * (c4 * c5 * c6 - s4 * s6) - s23 * s5 * c6) - s1 * (s4 * c5 * c6 + c4 * s6);
753  fMe[1][0] = -s1 * (c23 * (-c4 * c5 * c6 + s4 * s6) + s23 * s5 * c6) + c1 * (s4 * c5 * c6 + c4 * s6);
754  fMe[2][0] = s23 * (s4 * s6 - c4 * c5 * c6) - c23 * s5 * c6;
755 
756  fMe[0][1] = -c1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) + s1 * (s4 * c5 * s6 - c4 * c6);
757  fMe[1][1] = -s1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) - c1 * (s4 * c5 * s6 - c4 * c6);
758  fMe[2][1] = s23 * (c4 * c5 * s6 + s4 * c6) + c23 * s5 * s6;
759 
760  fMe[0][2] = c1 * (c23 * c4 * s5 + s23 * c5) - s1 * s4 * s5;
761  fMe[1][2] = s1 * (c23 * c4 * s5 + s23 * c5) + c1 * s4 * s5;
762  fMe[2][2] = -s23 * c4 * s5 + c23 * c5;
763 
764  fMe[0][3] = c1 * (c23 * (c4 * s5 * d6 - a3) + s23 * (c5 * d6 + d4) + a1 + a2 * c2) - s1 * s4 * s5 * d6;
765  fMe[1][3] = s1 * (c23 * (c4 * s5 * d6 - a3) + s23 * (c5 * d6 + d4) + a1 + a2 * c2) + c1 * s4 * s5 * d6;
766  fMe[2][3] = s23 * (a3 - c4 * s5 * d6) + c23 * (c5 * d6 + d4) - a2 * s2 + d1;
767 
768  // std::cout << "Effector position fMe: " << std::endl << fMe;
769 
770  return;
771 }
815 {
816  double q1 = q[0];
817  double q2 = q[1];
818  double q3 = q[2];
819  double q4 = q[3];
820  double q5 = q[4];
821  double q6 = q[5];
822  // We turn off the coupling since the measured positions are joint position
823  // taking into account the coupling factor. The coupling factor is relevant
824  // if positions are motor position.
825  // double q6 = q[5] + c56 * q[4];
826 
827  double c1 = cos(q1);
828  double s1 = sin(q1);
829  double c2 = cos(q2);
830  double s2 = sin(q2);
831  // double c3 = cos(q3);
832  // double s3 = sin(q3);
833  double c4 = cos(q4);
834  double s4 = sin(q4);
835  double c5 = cos(q5);
836  double s5 = sin(q5);
837  double c6 = cos(q6);
838  double s6 = sin(q6);
839  double c23 = cos(q2 + q3);
840  double s23 = sin(q2 + q3);
841 
842  fMw[0][0] = c1 * (c23 * (c4 * c5 * c6 - s4 * s6) - s23 * s5 * c6) - s1 * (s4 * c5 * c6 + c4 * s6);
843  fMw[1][0] = -s1 * (c23 * (-c4 * c5 * c6 + s4 * s6) + s23 * s5 * c6) + c1 * (s4 * c5 * c6 + c4 * s6);
844  fMw[2][0] = s23 * (s4 * s6 - c4 * c5 * c6) - c23 * s5 * c6;
845 
846  fMw[0][1] = -c1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) + s1 * (s4 * c5 * s6 - c4 * c6);
847  fMw[1][1] = -s1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) - c1 * (s4 * c5 * s6 - c4 * c6);
848  fMw[2][1] = s23 * (c4 * c5 * s6 + s4 * c6) + c23 * s5 * s6;
849 
850  fMw[0][2] = c1 * (c23 * c4 * s5 + s23 * c5) - s1 * s4 * s5;
851  fMw[1][2] = s1 * (c23 * c4 * s5 + s23 * c5) + c1 * s4 * s5;
852  fMw[2][2] = -s23 * c4 * s5 + c23 * c5;
853 
854  fMw[0][3] = c1 * (-c23 * a3 + s23 * d4 + a1 + a2 * c2);
855  fMw[1][3] = s1 * (-c23 * a3 + s23 * d4 + a1 + a2 * c2);
856  fMw[2][3] = s23 * a3 + c23 * d4 - a2 * s2 + d1;
857 
858  // std::cout << "Wrist position fMw: " << std::endl << fMw;
859 
860  return;
861 }
862 
874 {
875  // Set the rotation as identity
876  wMe.eye();
877 
878  // Set the translation
879  wMe[2][3] = d6;
880 }
881 
893 void vpViper::get_eMc(vpHomogeneousMatrix &eMc_) const { eMc_ = this->eMc; }
894 
905 {
906  eMs.eye();
907  eMs[2][3] = -d7; // tz = -d7
908 }
909 
921 void vpViper::get_cMe(vpHomogeneousMatrix &cMe) const { cMe = this->eMc.inverse(); }
922 
938 {
940  get_cMe(cMe);
941 
942  cVe.buildFrom(cMe);
943 
944  return;
945 }
946 
969 void vpViper::get_eJe(const vpColVector &q, vpMatrix &eJe) const
970 {
971  vpMatrix V(6, 6);
972  V = 0;
973  // Compute the first and last block of V
975  get_fMw(q, fMw);
976  vpRotationMatrix fRw;
977  fMw.extract(fRw);
978  vpRotationMatrix wRf;
979  wRf = fRw.inverse();
980  for (unsigned int i = 0; i < 3; i++) {
981  for (unsigned int j = 0; j < 3; j++) {
982  V[i][j] = V[i + 3][j + 3] = wRf[i][j];
983  }
984  }
985  // Compute the second block of V
987  get_wMe(wMe);
989  eMw = wMe.inverse();
991  eMw.extract(etw);
992  vpMatrix block2 = etw.skew() * wRf;
993  for (unsigned int i = 0; i < 3; i++) {
994  for (unsigned int j = 0; j < 3; j++) {
995  V[i][j + 3] = block2[i][j];
996  }
997  }
998  // Compute eJe
999  vpMatrix fJw;
1000  get_fJw(q, fJw);
1001  eJe = V * fJw;
1002 
1003  return;
1004 }
1005 
1053 void vpViper::get_fJw(const vpColVector &q, vpMatrix &fJw) const
1054 {
1055  double q1 = q[0];
1056  double q2 = q[1];
1057  double q3 = q[2];
1058  double q4 = q[3];
1059  double q5 = q[4];
1060 
1061  double c1 = cos(q1);
1062  double s1 = sin(q1);
1063  double c2 = cos(q2);
1064  double s2 = sin(q2);
1065  double c3 = cos(q3);
1066  double s3 = sin(q3);
1067  double c4 = cos(q4);
1068  double s4 = sin(q4);
1069  double c5 = cos(q5);
1070  double s5 = sin(q5);
1071  double c23 = cos(q2 + q3);
1072  double s23 = sin(q2 + q3);
1073 
1074  vpColVector J1(6);
1075  vpColVector J2(6);
1076  vpColVector J3(6);
1077  vpColVector J4(6);
1078  vpColVector J5(6);
1079  vpColVector J6(6);
1080 
1081  // Jacobian when d6 is set to zero
1082  J1[0] = -s1 * (-c23 * a3 + s23 * d4 + a1 + a2 * c2);
1083  J1[1] = c1 * (-c23 * a3 + s23 * d4 + a1 + a2 * c2);
1084  J1[2] = 0;
1085  J1[3] = 0;
1086  J1[4] = 0;
1087  J1[5] = 1;
1088 
1089  J2[0] = c1 * (s23 * a3 + c23 * d4 - a2 * s2);
1090  J2[1] = s1 * (s23 * a3 + c23 * d4 - a2 * s2);
1091  J2[2] = c23 * a3 - s23 * d4 - a2 * c2;
1092  J2[3] = -s1;
1093  J2[4] = c1;
1094  J2[5] = 0;
1095 
1096  J3[0] = c1 * (a3 * (s2 * c3 + c2 * s3) + (-s2 * s3 + c2 * c3) * d4);
1097  J3[1] = s1 * (a3 * (s2 * c3 + c2 * s3) + (-s2 * s3 + c2 * c3) * d4);
1098  J3[2] = -a3 * (s2 * s3 - c2 * c3) - d4 * (s2 * c3 + c2 * s3);
1099  J3[3] = -s1;
1100  J3[4] = c1;
1101  J3[5] = 0;
1102 
1103  J4[0] = 0;
1104  J4[1] = 0;
1105  J4[2] = 0;
1106  J4[3] = c1 * s23;
1107  J4[4] = s1 * s23;
1108  J4[5] = c23;
1109 
1110  J5[0] = 0;
1111  J5[1] = 0;
1112  J5[2] = 0;
1113  J5[3] = -c23 * c1 * s4 - s1 * c4;
1114  J5[4] = c1 * c4 - c23 * s1 * s4;
1115  J5[5] = s23 * s4;
1116 
1117  J6[0] = 0;
1118  J6[1] = 0;
1119  J6[2] = 0;
1120  J6[3] = (c1 * c23 * c4 - s1 * s4) * s5 + c1 * s23 * c5;
1121  J6[4] = (s1 * c23 * c4 + c1 * s4) * s5 + s1 * s23 * c5;
1122  J6[5] = -s23 * c4 * s5 + c23 * c5;
1123 
1124  fJw.resize(6, 6);
1125  for (unsigned int i = 0; i < 6; i++) {
1126  fJw[i][0] = J1[i];
1127  fJw[i][1] = J2[i];
1128  fJw[i][2] = J3[i];
1129  fJw[i][3] = J4[i];
1130  fJw[i][4] = J5[i];
1131  fJw[i][5] = J6[i];
1132  }
1133  return;
1134 }
1158 void vpViper::get_fJe(const vpColVector &q, vpMatrix &fJe) const
1159 {
1160  vpMatrix V(6, 6);
1161  V = 0;
1162  // Set the first and last block to identity
1163  for (unsigned int i = 0; i < 6; i++)
1164  V[i][i] = 1;
1165 
1166  // Compute the second block of V
1167  vpHomogeneousMatrix fMw;
1168  get_fMw(q, fMw);
1169  vpRotationMatrix fRw;
1170  fMw.extract(fRw);
1171  vpHomogeneousMatrix wMe;
1172  get_wMe(wMe);
1173  vpHomogeneousMatrix eMw;
1174  eMw = wMe.inverse();
1175  vpTranslationVector etw;
1176  eMw.extract(etw);
1177  vpMatrix block2 = (fRw * etw).skew();
1178  // Set the second block
1179  for (unsigned int i = 0; i < 3; i++)
1180  for (unsigned int j = 0; j < 3; j++)
1181  V[i][j + 3] = block2[i][j];
1182 
1183  // Compute fJe
1184  vpMatrix fJw;
1185  get_fJw(q, fJw);
1186  fJe = V * fJw;
1187 
1188  return;
1189 }
1190 
1199 
1208 
1219 double vpViper::getCoupl56() const { return c56; }
1220 
1230 {
1231  this->eMc = eMc_;
1232  this->eMc.extract(etc);
1233  vpRotationMatrix R(this->eMc);
1234  this->erc.buildFrom(R);
1235 }
1236 
1247 void vpViper::set_eMc(const vpTranslationVector &etc_, const vpRxyzVector &erc_)
1248 {
1249  this->etc = etc_;
1250  this->erc = erc_;
1251  vpRotationMatrix eRc(erc);
1252  this->eMc.buildFrom(etc, eRc);
1253 }
1254 
1264 VISP_EXPORT 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 << "Joint Max (deg):" << std::endl
1277  << "\t" << jmax.t() << std::endl
1278 
1279  << "Joint Min (deg): " << std::endl
1280  << "\t" << jmin.t() << std::endl
1281 
1282  << "Coupling 5-6:" << std::endl
1283  << "\t" << viper.c56 << std::endl
1284 
1285  << "eMc: " << std::endl
1286  << "\tTranslation (m): " << viper.eMc[0][3] << " " << viper.eMc[1][3] << " " << viper.eMc[2][3] << "\t"
1287  << std::endl
1288  << "\tRotation Rxyz (rad) : " << rxyz[0] << " " << rxyz[1] << " " << rxyz[2] << "\t" << std::endl
1289  << "\tRotation Rxyz (deg) : " << vpMath::deg(rxyz[0]) << " " << vpMath::deg(rxyz[1]) << " " << vpMath::deg(rxyz[2])
1290  << "\t" << std::endl;
1291 
1292  return os;
1293 }
1294 END_VISP_NAMESPACE
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
Definition: vpArray2D.h:362
friend std::ostream & operator<<(std::ostream &s, const vpArray2D< Type > &A)
Definition: vpArray2D.h:614
unsigned int getRows() const
Definition: vpArray2D.h:347
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
vpColVector & rad2deg()
Definition: vpColVector.h:1053
vpRowVector t() const
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:1143
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
void extract(vpRotationMatrix &R) const
static double rad(double deg)
Definition: vpMath.h:129
static double sqr(double x)
Definition: vpMath.h:203
static double deg(double rad)
Definition: vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
Implementation of a rotation matrix and operations on such kind of matrices.
vpRotationMatrix inverse() const
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:183
vpRxyzVector & buildFrom(const vpRotationMatrix &R)
Class that consider the case of a translation vector.
vpVelocityTwistMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
Modelization of the ADEPT Viper robot.
Definition: vpViper.h:113
double getCoupl56() const
Definition: vpViper.cpp:1219
void get_fJw(const vpColVector &q, vpMatrix &fJw) const
Definition: vpViper.cpp:1053
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
Definition: vpViper.cpp:1229
vpHomogeneousMatrix getForwardKinematics(const vpColVector &q) const
Definition: vpViper.cpp:119
void get_fMw(const vpColVector &q, vpHomogeneousMatrix &fMw) const
Definition: vpViper.cpp:814
vpTranslationVector etc
Definition: vpViper.h:158
double d6
for joint 6
Definition: vpViper.h:166
double a3
for joint 3
Definition: vpViper.h:164
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:153
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:921
double d4
for joint 4
Definition: vpViper.h:165
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpViper.cpp:1158
vpColVector joint_max
Definition: vpViper.h:171
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:568
double c56
Mechanical coupling between joint 5 and joint 6.
Definition: vpViper.h:168
vpColVector getJointMin() const
Definition: vpViper.cpp:1198
void get_eMc(vpHomogeneousMatrix &eMc) const
Definition: vpViper.cpp:893
vpHomogeneousMatrix eMc
End effector to camera transformation.
Definition: vpViper.h:156
double a1
Definition: vpViper.h:162
vpRxyzVector erc
Definition: vpViper.h:159
vpColVector getJointMax() const
Definition: vpViper.cpp:1207
vpColVector joint_min
Definition: vpViper.h:172
void get_eMs(vpHomogeneousMatrix &eMs) const
Definition: vpViper.cpp:904
double a2
for joint 2
Definition: vpViper.h:163
vpViper()
Definition: vpViper.cpp:63
void get_wMe(vpHomogeneousMatrix &wMe) const
Definition: vpViper.cpp:873
unsigned int getInverseKinematicsWrist(const vpHomogeneousMatrix &fMw, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:220
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpViper.cpp:969
double d1
for joint 1
Definition: vpViper.h:162
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
Definition: vpViper.cpp:724
void get_cVe(vpVelocityTwistMatrix &cVe) const
Definition: vpViper.cpp:937
double d7
for force/torque location
Definition: vpViper.h:167
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:605