kinecalc.cc

00001 /*
00002  *  Player - One Hell of a Robot Server
00003  *  Copyright (C) 2000
00004  *     Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard
00005  *
00006  *
00007  *  This program is free software; you can redistribute it and/or modify
00008  *  it under the terms of the GNU General Public License as published by
00009  *  the Free Software Foundation; either version 2 of the License, or
00010  *  (at your option) any later version.
00011  *
00012  *  This program is distributed in the hope that it will be useful,
00013  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00014  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00015  *  GNU General Public License for more details.
00016  *
00017  *  You should have received a copy of the GNU General Public License
00018  *  along with this program; if not, write to the Free Software
00019  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00020  *
00021  */
00022 
00023 /*  Kinematics calculator implementation based on the analytical method by
00024  *  Gan et al. See:
00025  *  J.Q. Gan, E. Oyama, E.M. Rosales, and H. Hu, "A complete analytical
00026  *  solution to the inverse kinematics of the Pioneer 2 robotic arm,"
00027  *  Robotica, vol.23, no.1, pp.123-129, 2005.
00028  */
00029 
00030 #include <libplayercore/playercommon.h>
00031 #include <libplayercore/error.h>
00032 #include "kinecalc.h"
00033 
00034 #include <math.h>
00035 
00036 #include <stdio.h>
00037 
00038 KineCalc::KineCalc (void)
00039 {
00040   link1 = 0.06875f;
00041   link2 = 0.16f;
00042   link3 = 0.0f;
00043   link4 = 0.13775f;
00044   link5 = 0.11321f;
00045 
00046   endEffector.p.x = 0.0f; endEffector.p.y = 0.0f; endEffector.p.z = 0.0f;
00047   endEffector.n.x = 0.0f; endEffector.n.y = 0.0f; endEffector.n.z = 0.0f;
00048   endEffector.o.x = 0.0f; endEffector.o.y = -1.0f; endEffector.o.z = 1.0f;
00049   endEffector.a.x = 1.0f; endEffector.a.y = 0.0f; endEffector.a.z = 0.0f;
00050 
00051   for (int ii = 0; ii < 5; ii++)
00052   {
00053     joints[ii] = 0.0f;
00054     jointOffsets[ii] = 0.0f;
00055     jointMin[ii] = 0.0f;
00056     jointMax[ii] = 0.0f;
00057   }
00058 }
00059 
00060 
00062 //  Accessor functions
00064 
00065 void KineCalc::SetP (double newPX, double newPY, double newPZ)
00066 {
00067   endEffector.p.x = newPX;
00068   endEffector.p.y = newPY;
00069   endEffector.p.z = newPZ;
00070 }
00071 
00072 void KineCalc::SetN (double newNX, double newNY, double newNZ)
00073 {
00074   endEffector.n.x = newNX;
00075   endEffector.n.y = newNY;
00076   endEffector.n.z = newNZ;
00077 }
00078 
00079 void KineCalc::SetO (double newOX, double newOY, double newOZ)
00080 {
00081   endEffector.o.x = newOX;
00082   endEffector.o.y = newOY;
00083   endEffector.o.z = newOZ;
00084 }
00085 
00086 void KineCalc::SetA (double newAX, double newAY, double newAZ)
00087 {
00088   endEffector.a.x = newAX;
00089   endEffector.a.y = newAY;
00090   endEffector.a.z = newAZ;
00091 }
00092 
00093 double KineCalc::GetTheta (unsigned int index)
00094 {
00095   return joints[index];
00096 }
00097 
00098 void KineCalc::SetTheta (unsigned int index, double newVal)
00099 {
00100   joints[index] = newVal;
00101 }
00102 
00103 void KineCalc::SetLinkLengths (double newLink1, double newLink2, double newLink3, double newLink4, double newLink5)
00104 {
00105   link1 = newLink1;
00106   link2 = newLink2;
00107   link3 = newLink3;
00108   link4 = newLink4;
00109   link5 = newLink5;
00110 }
00111 
00112 void KineCalc::SetOffset (unsigned int joint, double newOffset)
00113 {
00114   jointOffsets[joint] = newOffset;
00115 }
00116 
00117 void KineCalc::SetJointRange (unsigned int joint, double min, double max)
00118 {
00119   jointMin[joint] = MIN (min, max);   // So that if min > max we reverse them
00120   jointMax[joint] = MAX (min, max);
00121 }
00122 
00123 
00124 
00126 //  Utility helper functions
00128 
00129 KineVector KineCalc::Normalise (const KineVector &vector)
00130 {
00131   KineVector result;
00132   double length = sqrt (vector.x * vector.x + vector.y * vector.y + vector.z * vector.z);
00133   if (length != 0)
00134   {
00135     result.x = vector.x / length;
00136     result.y = vector.y / length;
00137     result.z = vector.z / length;
00138   }
00139   else
00140   {
00141     PLAYER_WARN ("P2OS: Tried to normalise a vector of zero length.");
00142     result.x = 0;
00143     result.y = 0;
00144     result.z = 0;
00145   }
00146   return result;
00147 }
00148 
00149 KineVector KineCalc::CalculateN (const EndEffector &pose)
00150 {
00151   KineVector result;
00152   result.x = pose.o.y * pose.a.z - pose.a.y * pose.o.z;
00153   result.y = pose.o.z * pose.a.x - pose.a.z * pose.o.x;
00154   result.z = pose.o.x * pose.a.y - pose.a.x * pose.o.y;
00155   if (result.x == 0 && result.y == 0 && result.z == 0)
00156   {
00157     PLAYER_WARN ("P2OS: Approach and orientation cannot be the same vector - their cross product cannot be zero.");
00158     // Ensures that a different orientation vector is created
00159     KineVector orient;
00160     if (pose.a.y == 0 && pose.a.z == 0)
00161     {
00162       orient.x = 0;
00163       orient.y = 1;
00164       orient.z = 0;
00165     }
00166     else
00167     {
00168       orient.x = 1;
00169       orient.y = 0;
00170       orient.z = 0;
00171     }
00172     result.x = orient.y * pose.a.z - pose.a.y * orient.z;
00173     result.y = orient.z * pose.a.x - pose.a.z * orient.x;
00174     result.z = orient.x * pose.a.y - pose.a.x * orient.y;
00175   }
00176   return Normalise (result);
00177 }
00178 
00179 void KineCalc::PrintEndEffector (const EndEffector &endEffector)
00180 {
00181   printf ("P: (%f, %f, %f)\tA: (%f, %f, %f)\tO: (%f, %f, %f)\tN: (%f, %f, %f)\n",
00182           endEffector.p.x, endEffector.p.y, endEffector.p.z,
00183           endEffector.a.x, endEffector.a.y, endEffector.a.z,
00184           endEffector.o.x, endEffector.o.y, endEffector.o.z,
00185           endEffector.n.x, endEffector.n.y, endEffector.n.z);
00186 }
00187 
00188 
00190 //  The important functions
00192 
00193 //  Calculate the forward kinematics
00194 //  The result is stored in endEffector
00195 //  fromJoints[]:   An array of 5 joint values
00196 void KineCalc::CalculateFK (const double fromJoints[])
00197 {
00198   double adjustedJoints[5];
00199 
00200   adjustedJoints[0] = (fromJoints[0] - jointOffsets[0]) * -1;
00201   adjustedJoints[1] = fromJoints[1] - jointOffsets[1];
00202   adjustedJoints[2] = fromJoints[2] - jointOffsets[2];
00203   adjustedJoints[3] = (fromJoints[3] - jointOffsets[3]) * -1;;
00204   adjustedJoints[4] = (fromJoints[4] - jointOffsets[4]) * -1;;
00205 
00206   endEffector = CalcFKForJoints (adjustedJoints);
00207 //  printf ("Result of FK:\n");
00208 //  PrintEndEffector (endEffector);
00209 }
00210 
00211 //  Calculate the inverse kinematics
00212 //  The result is stored in joints
00213 //  fromPosition:   An EndEffector structure describing the pose
00214 //                  of the end effector
00215 bool KineCalc::CalculateIK (const EndEffector &fromPosition)
00216 {
00217   // Some references to make the code neater
00218   const KineVector &p = fromPosition.p;
00219   const KineVector &a = fromPosition.a;
00220   // These are the four possible solutions to the IK
00221   // solution1 = {1a, 2a, 3a, 4a, 5a}
00222   // solution2 = {1a, 2b, 3b, 4b, 5b}
00223   // solution3 = {1b, 2c, 3c, 4c, 5c}
00224   // solution4 = {1b, 2d, 3d, 4d, 5d}
00225   double solutions[4][5];
00226   double temp = 0.0f;
00227 
00228   // First calculate the two possible values for theta1, theta1a and theta1b
00229   temp = atan2 (p.y - link5 * a.y, p.x - link5 * a.x);
00230   solutions[0][0] = solutions[1][0] = temp;
00231   temp = atan2 (link5 * a.y - p.y, link5 * a.x - p.x);
00232   solutions[2][0] = solutions[3][0] = temp;
00233 
00234   // Next, using theta1_a, calculate thetas 2 and 3 (a and b)
00235   // First up is calculating r and rz
00236   double r = 0.0f, rz = 0.0f;
00237   if (sin (solutions[0][0]) < 0.1f && sin(solutions[0][0]) > -0.1f)
00238   {
00239     r = ((p.x - (link5 * a.x)) / cos (solutions[0][0])) - link1;
00240   }
00241   else
00242   {
00243     r = ((p.y - (link5 * a.y)) / sin (solutions[0][0])) - link1;
00244   }
00245   rz = p.z - (link5 * a.z);
00246   // Then calculate theta2a and 3a
00247   temp = (r * r + rz * rz + link2 * link2 - link4 * link4) / (2 * link2 * sqrt (r * r + rz * rz));
00248   temp = MIN (MAX (temp, -1.0f), 1.0f);
00249   temp = atan2 (rz, r) - acos (temp);
00250   int m1 = -1;
00251   do
00252   {
00253     if (m1 > 1)
00254     {
00255       printf ("m1 > 1!\n");
00256       break;
00257     }
00258     solutions[0][1] = temp + 2 * m1 * M_PI;
00259     m1 += 1;  // So that within the 3 iterations we get m1 = -1, 0, 1
00260   } // Put a catchall here to prevent infinite loops by checking if m1 has gone past 1 (shouldn't happen)
00261   while ((solutions[0][1] < -(M_PI) || solutions[0][1] > M_PI));// && m1 < 1);
00262   temp = (link2 * link2 + link4 * link4 - r * r - rz * rz) / (2 * link2 * link4);
00263   temp = MIN (MAX (temp, -1.0f), 1.0f);
00264   solutions[0][2] = M_PI - acos (temp);
00265   // Followed by theta2b and 3b
00266   temp = (r * r + rz * rz + link2 * link2 - link4 * link4) / (2 * link2 * sqrt (r * r + rz * rz));
00267   temp = MIN (MAX (temp, -1.0f), 1.0f);
00268   temp = atan2 (rz, r) + acos (temp);
00269   m1 = -1;
00270   do
00271   {
00272     if (m1 > 1)
00273     {
00274       break;
00275     }
00276     solutions[1][1] = temp + 2 * m1 * M_PI;
00277     m1 += 1;  // So that within the 3 iterations we get m1 = -1, 0, 1
00278   }
00279   while ((solutions[1][1] < -(M_PI) || solutions[1][1] > M_PI));// && m1 < 1);
00280   temp = (link2 * link2 + link4 * link4 - r * r - rz * rz) / (2 * link2 * link4);
00281   temp = MIN (MAX (temp, -1.0f), 1.0f);
00282   solutions[1][2] = -(M_PI) + acos (temp);
00283 
00284   // Using theta2a and 3a, calculate 4a and 5a to complete solution1
00285   CalcTheta4and5 (solutions[0], fromPosition);
00286   // Using theta2b and 3b, calculate 4b and 5b to complete solution2
00287   CalcTheta4and5 (solutions[1], fromPosition);
00288 
00289   // That's two of the possible solutions. To get the other two, repeat with theta1b
00290   // First up is calculating r and rz
00291   r = 0.0f;
00292   rz = 0.0f;
00293   if (sin (solutions[2][0]) < 0.1f && sin(solutions[2][0]) > -0.1f)
00294   {
00295     r = (p.x - link5 * a.x) / cos (solutions[2][0]) - link1;
00296   }
00297   else
00298   {
00299     r = (p.y - link5 * a.y) / sin (solutions[2][0]) - link1;
00300   }
00301   rz = p.z - (link5 * a.z);
00302   // Then calculate theta2c and 3c
00303   temp = (r * r + rz * rz + link2 * link2 - link4 * link4) / (2 * link2 * sqrt (r * r + rz * rz));
00304   temp = MIN (MAX (temp, -1.0f), 1.0f);
00305   temp = atan2 (rz, r) - acos (temp);
00306   m1 = -1;
00307   do
00308   {
00309     if (m1 > 1)
00310     {
00311       break;
00312     }
00313     solutions[2][1] = temp + 2 * m1 * M_PI;
00314     m1 += 1;  // So that within the 3 iterations we get m1 = -1, 0, 1
00315   } // Put a catchall here to prevent infinite loops by checking if m1 has gone past 1 (shouldn't happen)
00316   while ((solutions[2][1] < -(M_PI) || solutions[2][1] > M_PI));// && m1 < 1);
00317   temp = (link2 * link2 + link4 * link4 - r * r - rz * rz) / (2 * link2 * link4);
00318   temp = MIN (MAX (temp, -1.0f), 1.0f);
00319   solutions[2][2] = M_PI - acos (temp);
00320   // Followed by theta2d and 3d
00321   temp = (r * r + rz * rz + link2 * link2 - link4 * link4) / (2 * link2 * sqrt (r * r + rz * rz));
00322   temp = MIN (MAX (temp, -1.0f), 1.0f);
00323   temp = atan2 (rz, r) + acos (temp);
00324   m1 = -1;
00325   do
00326   {
00327     if (m1 > 1)
00328     {
00329       break;
00330     }
00331     solutions[3][1] = temp + 2 * m1 * M_PI;
00332     m1 += 1;  // So that within the 3 iterations we get m1 = -1, 0, 1
00333   }
00334   while ((solutions[3][1] < -(M_PI) || solutions[3][1] > M_PI));// && m1 < 1);
00335   temp = (link2 * link2 + link4 * link4 - r * r - rz * rz) / (2 * link2 * link4);
00336   temp = MIN (MAX (temp, -1.0f), 1.0f);
00337   solutions[3][2] = -(M_PI) + acos (temp);
00338 
00339   // Using theta2c and 3c, calculate 4c and 5c to complete solution1
00340   CalcTheta4and5 (solutions[2], fromPosition);
00341   // Using theta2d and 3d, calculate 4d and 5d to complete solution2
00342   CalcTheta4and5 (solutions[3], fromPosition);
00343 
00344   // Choose the best of the four solutions
00345   int chosenSolution = ChooseSolution (fromPosition, solutions);
00346   if (chosenSolution == -1)
00347     // Couldn't find a valid solution
00348     return false;
00349 
00350   // Offsets and so forth
00351   joints[0] = (solutions[chosenSolution][0] * -1) + jointOffsets[0];
00352   joints[1] = solutions[chosenSolution][1] + jointOffsets[1];
00353   joints[2] = solutions[chosenSolution][2] + jointOffsets[2];
00354   joints[3] = (solutions[chosenSolution][3] * -1) + jointOffsets[3];
00355   joints[4] = (solutions[chosenSolution][4] * -1) + jointOffsets[4];
00356 
00357   return true;
00358 }
00359 
00360 //  Calculates thetas 4 and 5 based on supplied thetas 1, 2 and 3 and the desired end effector pose
00361 //  angles[]:       A 5-element array, of which elements 0, 1 and 2 should be filled already
00362 //  fromPosition:   The desired end effector pose
00363 void KineCalc::CalcTheta4and5 (double angles[], const EndEffector &fromPosition)
00364 {
00365   const KineVector &n = fromPosition.n;
00366   const KineVector &o = fromPosition.o;
00367   const KineVector &a = fromPosition.a;
00368 
00369   double cos1 = cos (angles[0]);
00370   double cos23 = cos (angles[1] + angles[2]);
00371   double sin1 = sin (angles[0]);
00372   double sin23 = sin (angles[1] + angles[2]);
00373 
00374   if (cos23 != 0.0f)
00375   {
00376     if (sin1 < -0.1f || sin1 > 0.1f)
00377     {
00378       angles[3] = atan2 (n.z / cos23, -(n.x + ((n.z * cos1 * sin23) / cos23)) / sin1);
00379     }
00380     else
00381     {
00382       angles[3] = atan2 (n.z / cos23, (n.y + ((n.z * sin1 * sin23) / cos23)) / cos1);
00383     }
00384 
00385     double cos4 = cos (angles[3]);
00386     double sin4 = sin (angles[3]);
00387     if (cos4 != 0 || sin23 != 0)
00388     {
00389       angles[4] = atan2 (a.z * cos23 * cos4 - o.z * sin23, o.z * cos23 * cos4 + a.z * sin23);
00390     }
00391     else
00392     {
00393       angles[4] = atan2 (-(o.x * cos1 + o.y * sin1) / cos23, (o.x * sin1 - o.y * cos1) / sin4);
00394     }
00395   }
00396   else
00397   {
00398     angles[4] = atan2 (-o.z / sin23, a.z / sin23);
00399 
00400     double cos5 = cos (angles[4]);
00401     double sin5 = sin (angles[4]);
00402     if (cos5 > -0.1f || cos5 < 0.1f)
00403     {
00404       angles[3] = atan2 ((a.x * sin1 - a.y * cos1) / sin5, -(n.x * sin1) + n.y * cos1);
00405     }
00406     else
00407     {
00408       angles[3] = atan2 ((o.x * sin1 - o.y * cos1) / cos5, -(n.x * sin1) + n.y * cos1);
00409     }
00410   }
00411 }
00412 
00413 //  Choose the best solution from the 4 available based on error and reachability
00414 //  fromPosition:   The desired end effector pose
00415 //  solutions[][]:  The four solutions (each with 5 angles) in an array
00416 int KineCalc::ChooseSolution (const EndEffector &fromPosition, const double solutions[][5])
00417 {
00418   double errors[4];
00419   int order[4], jj;
00420 
00421   // We have 4 solutions, calculate the error for each one
00422   errors[0] = CalcSolutionError (solutions[0], fromPosition);
00423   errors[1] = CalcSolutionError (solutions[1], fromPosition);
00424   errors[2] = CalcSolutionError (solutions[2], fromPosition);
00425   errors[3] = CalcSolutionError (solutions[3], fromPosition);
00426 
00427   for (int ii = 0; ii < 4; ii++)
00428   {
00429     double min = MIN (errors[0], MIN (errors[1], MIN (errors[2], errors[3])));
00430     for (jj = 0; min != errors[jj]; jj++);  // Find the index at which the min is at
00431     errors[jj] = 999999;
00432     order[ii] = jj;
00433   }
00434 
00435   for (int ii = 0; ii < 4; ii++)
00436   {
00437     if (SolutionInRange (solutions[order[ii]]))
00438     {
00439       return order[ii];
00440     }
00441   }
00442 
00443   return -1;
00444 }
00445 
00446 //  Calculate the error for a solution from the desired pose
00447 //  solution[]:       An array of 5 angles
00448 //  fromPosition[]:   The end effector pose
00449 double KineCalc::CalcSolutionError (const double solution[], const EndEffector &fromPosition)
00450 {
00451   EndEffector solutionPos;
00452   double error = 0.0f;
00453 
00454   // Calculate the position of the end effector this solution gives using FK
00455   solutionPos = CalcFKForJoints (solution);
00456   // Calculate the distance from this to the desired position
00457   double xOffset = solutionPos.p.x - fromPosition.p.x;
00458   double yOffset = solutionPos.p.y - fromPosition.p.y;
00459   double zOffset = solutionPos.p.z - fromPosition.p.z;
00460 
00461   error = sqrt (xOffset * xOffset + yOffset * yOffset + zOffset * zOffset);
00462   if (isnan (error))
00463     error = 9999;
00464 
00465   return error;
00466 }
00467 
00468 //  Calculates the forward kinematics of a set of joint angles
00469 //  angles[]:   The 5 angles to calculate from
00470 EndEffector KineCalc::CalcFKForJoints (const double angles[])
00471 {
00472   EndEffector result;
00473 
00474   double cos1 = cos (angles[0]);
00475   double cos2 = cos (angles[1]);
00476   double cos23 = cos (angles[1] + angles[2]);
00477   double cos4 = cos (angles[3]);
00478   double cos5 = cos (angles[4]);
00479   double sin1 = sin (angles[0]);
00480   double sin2 = sin (angles[1]);
00481   double sin23 = sin (angles[1] + angles[2]);
00482   double sin4 = sin (angles[3]);
00483   double sin5 = sin (angles[4]);
00484 
00485   result.p.x = link5 * ((cos1 * cos23 * cos5) + (sin1 * sin4 * sin5) - (cos1 * sin23 * cos4 * sin5)) +
00486       cos1 * ((link4 * cos23) + (link2 * cos2) + link1);
00487   result.p.y = link5 * ((sin1 * cos23 * cos5) + (cos1 * sin4 * sin5) - (sin1 * sin23 * cos4 * sin5)) +
00488       sin1 * ((link4 * cos23) + (link2 * cos2) + link1);
00489   result.p.z = link5 * ((sin23 * cos5) + (cos23 * cos4 * sin5)) + (link4 * sin23) + (link2 * sin2);
00490 
00491   result.n.x = -(sin1 * cos4) - (cos1 * sin23 * sin4);
00492   result.n.y = (cos1 * cos4) - (sin1 * sin23 * sin4);
00493   result.n.z = (cos23 * sin4);
00494 
00495   result.o.x = -(cos1 * cos23 * sin5) + (sin1 * sin4 * cos5) - (cos1 * sin23 * cos4 * cos5);
00496   result.o.y = -(sin1 * cos23 * sin5) - (cos1 * sin4 * cos5) - (sin1 * sin23 * cos4 * cos5);
00497   result.o.z = -(sin23 * sin5) + (cos23 * cos4 * cos5);
00498 
00499   result.a.x = (cos1 * cos23 * cos5) + (sin1 * sin4 * sin5) - (cos1 * sin23 * cos4 * sin5);
00500   result.a.y = (sin1 * cos23 * cos5) + (cos1 * sin4 * sin5) - (sin1 * sin23 * cos4 * sin5);
00501   result.a.z = (sin23 * cos5) + (cos23 * cos4 * sin5);
00502 
00503   return result;
00504 }
00505 
00506 //  Checks if the angles for a solution are reachable by the arm
00507 //  angles[]:   The 5 angles to check
00508 bool KineCalc::SolutionInRange (const double angles[])
00509 {
00510   for (int ii = 0; ii < 5; ii++)
00511   {
00512     if (angles[ii] < jointMin[ii] || angles[ii] > jointMax[ii] || isnan(angles[ii]))
00513       return false;
00514   }
00515 
00516   return true;
00517 }

Last updated 12 September 2005 21:38:45