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>
67 : eMc(), etc(), erc(), a1(0), d1(0), a2(), a3(), d4(0), d6(0), c56(0), joint_max(), joint_min()
78 c56 = -341.33 / 9102.22;
148 vpViper::convertJointPositionInLimits(
unsigned int joint,
const double &q,
double &q_mod,
const bool &verbose)
const
167 std::cout <<
"Joint " << joint <<
" not in limits: "
168 << this->
joint_min[joint] <<
" < " << q <<
" < " << this->
joint_max[joint] << std::endl;
232 for (
unsigned int i=0; i<8; i++)
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};
253 for (
unsigned int i=0; i< 8; i++)
256 double px = fMw[0][3];
257 double py = fMw[1][3];
258 double pz = fMw[2][3];
261 double a_2 = px*px+py*py;
263 if (std::fabs(a_2) <= std::numeric_limits<double>::epsilon()) {
266 c1[4] = cos(q[0]+M_PI);
267 s1[4] = sin(q[0]+M_PI);
270 double a = sqrt(a_2);
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++) {
285 q_sol[i+j][0] = q_sol[i][0];
289 for(
unsigned int j=1;j<4;j++)
296 for(
unsigned int i=0; i<8; i+=4) {
299 - 2*(
a1*c1[i]*px +
a1*s1[i]*py +
d1*pz)) / (2*
a2);
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));
305 for (
unsigned int j=0; j<4; j+=2) {
307 for(
unsigned int k=0; k<2; k++)
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);
319 for(
unsigned int k=0; k<2; k++)
332 double q23[8], q2_mod;
333 for (
unsigned int i=0; i<8; i+=2) {
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]);
343 q_sol[i][1] = q23[i] - q_sol[i][2];
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;
353 for(
unsigned int j=0; j<2; j++)
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) {
370 s4s5 = -s1[i]*r13+c1[i]*r23;
371 c4s5 = c1[i]*c23[i]*r13+s1[i]*c23[i]*r23-s23[i]*r33;
374 c5[i] = c1[i]*s23[i]*r13+s1[i]*s23[i]*r23+c23[i]*r33;
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];
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]);
390 for(
unsigned int j=0; j<2; j++)
397 if (std::fabs(c4s5) <= std::numeric_limits<double>::epsilon()) {
401 q_sol[i][3] = atan2(s4s5, c4s5);
404 q_sol[i][3] = atan2(s4s5, c4s5);
406 if (convertJointPositionInLimits(3, q_sol[i][3], q4_mod, verbose) ==
true) {
407 q_sol[i][3] = q4_mod;
414 if (q_sol[i][3] > 0.)
415 q_sol[i+1][3] = q_sol[i][3] + M_PI;
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);
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;
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;
450 double r12 = fMw[0][1];
451 double r22 = fMw[1][1];
452 double r32 = fMw[2][1];
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;
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;
472 unsigned int nbsol = 0;
473 unsigned int sol = 0;
475 for (
unsigned int i=0; i<8; i++) {
483 weight[1] = weight[2] = 4;
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;
493 if (fabs(rought_dist + 2*M_PI) < fabs(rought_dist))
494 modulo_dist = rought_dist + 2*M_PI;
504 for (
unsigned int i=0; i<8; i++) {
506 if (dist[i] < dist[sol]) sol = i;
650 fMc = fMe * this->
eMc;
758 double c23 = cos(q2+q3);
759 double s23 = sin(q2+q3);
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;
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;
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;
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;
854 double c23 = cos(q2+q3);
855 double s23 = sin(q2+q3);
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;
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;
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;
869 fMw[0][3] = c1*(-c23*
a3+s23*
d4+
a1+
a2*c2);
870 fMw[1][3] = s1*(-c23*
a3+s23*
d4+
a1+
a2*c2);
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];
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];
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);
1096 J1[0] = -s1*(-c23*
a3+s23*
d4+
a1+
a2*c2);
1097 J1[1] = c1*(-c23*
a3+s23*
d4+
a1+
a2*c2);
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;
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);
1127 J5[3] = -c23*c1*s4-s1*c4;
1128 J5[4] = c1*c4-c23*s1*s4;
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;
1139 for (
unsigned int i=0;i<6;i++) {
1178 for (
unsigned int i=0; i<6; i++ )
1192 vpMatrix block2 = (fRw*etw).skew();
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];
1307 <<
"Joint Max (deg):" << std::endl
1308 <<
"\t" << jmax.
t() << std::endl
1310 <<
"Joint Min (deg): " << std::endl
1311 <<
"\t" << jmin.
t() << std::endl
1313 <<
"Coupling 5-6:" << std::endl
1314 <<
"\t" << viper.
c56 << std::endl
1316 <<
"eMc: "<< std::endl
1317 <<
"\tTranslation (m): "
1318 << viper.
eMc[0][3] <<
" "
1319 << viper.
eMc[1][3] <<
" "
1321 <<
"\t" << std::endl
1322 <<
"\tRotation Rxyz (rad) : "
1326 <<
"\t" << std::endl
1327 <<
"\tRotation Rxyz (deg) : "
1331 <<
"\t" << std::endl;
void get_cVe(vpVelocityTwistMatrix &cVe) const
Implementation of a matrix and operations on matrices.
vpRxyzVector buildFrom(const vpRotationMatrix &R)
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
void get_fMw(const vpColVector &q, vpHomogeneousMatrix &fMw) const
vpHomogeneousMatrix eMc
End effector to camera transformation.
vpRotationMatrix inverse() const
Modelisation of the ADEPT Viper robot.
double getCoupl56() const
void resize(const unsigned int nrows, const unsigned int ncols, const bool flagNullify=true)
unsigned int getInverseKinematicsWrist(const vpHomogeneousMatrix &fMw, vpColVector &q, const bool &verbose=false) const
void get_wMe(vpHomogeneousMatrix &wMe) const
Implementation of an homogeneous matrix and operations on such kind of matrices.
void get_eMc(vpHomogeneousMatrix &eMc) const
Implementation of a rotation matrix and operations on such kind of matrices.
double c56
Mechanical coupling between joint 5 and joint 6.
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double sqr(double x)
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
friend std::ostream & operator<<(std::ostream &s, const vpArray2D< Type > &A)
void get_fJw(const vpColVector &q, vpMatrix &fJw) const
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.
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double rad(double deg)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
vpColVector getJointMin() const
void get_cMe(vpHomogeneousMatrix &cMe) const
static double deg(double rad)
vpColVector getJointMax() const
Implementation of column vector and the associated operations.
vpHomogeneousMatrix inverse() const
Implementation of a rotation vector as Euler angle minimal representation.
vpHomogeneousMatrix getForwardKinematics(const vpColVector &q) const
Class that consider the case of a translation vector.
static const unsigned int njoint
Number of joint.
void resize(const unsigned int i, const bool flagNullify=true)