pr2_arm_ik.cpp
Go to the documentation of this file.
00001 //Software License Agreement (BSD License)
00002 
00003 //Copyright (c) 2008, Willow Garage, Inc.
00004 //All rights reserved.
00005 
00006 //Redistribution and use in source and binary forms, with or without
00007 //modification, are permitted provided that the following conditions
00008 //are met:
00009 
00010 // * Redistributions of source code must retain the above copyright
00011 //   notice, this list of conditions and the following disclaimer.
00012 // * Redistributions in binary form must reproduce the above
00013 //   copyright notice, this list of conditions and the following
00014 //   disclaimer in the documentation and/or other materials provided
00015 //   with the distribution.
00016 // * Neither the name of Willow Garage, Inc. nor the names of its
00017 //   contributors may be used to endorse or promote products derived
00018 //   from this software without specific prior written permission.
00019 
00020 //THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 //"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 //LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 //FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 //COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 //INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 //BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 //LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 //CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 //LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 //ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 //POSSIBILITY OF SUCH DAMAGE.
00032 
00033 #include <angles/angles.h>
00034 #include <moveit/pr2_arm_kinematics/pr2_arm_ik.h>
00035 
00036 /**** List of angles (for reference) *******
00037       th1 = shoulder/turret pan
00038       th2 = shoulder/turret lift/pitch
00039       th3 = shoulder/turret roll
00040       th4 = elbow pitch
00041       th5 = elbow roll
00042       th6 = wrist pitch
00043       th7 = wrist roll
00044 *****/
00045 using namespace angles;
00046 using namespace pr2_arm_kinematics;
00047 
00048 PR2ArmIK::PR2ArmIK()
00049 {
00050 }
00051 
00052 bool PR2ArmIK::init(const urdf::Model &robot_model, const std::string &root_name, const std::string &tip_name)
00053 {
00054   std::vector<urdf::Pose> link_offset;
00055   int num_joints = 0;
00056   boost::shared_ptr<const urdf::Link> link = robot_model.getLink(tip_name);
00057   while(link && num_joints < 7)
00058   {
00059     boost::shared_ptr<const urdf::Joint> joint;
00060     if (link->parent_joint)
00061       joint = robot_model.getJoint(link->parent_joint->name);
00062     if(!joint)
00063     {
00064       if (link->parent_joint)
00065         ROS_ERROR("Could not find joint: %s",link->parent_joint->name.c_str());
00066       else
00067         ROS_ERROR("Link %s has no parent joint",link->name.c_str());
00068       return false;
00069     }
00070     if(joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
00071     {
00072       link_offset.push_back(link->parent_joint->parent_to_joint_origin_transform);
00073       angle_multipliers_.push_back(joint->axis.x*fabs(joint->axis.x) +  joint->axis.y*fabs(joint->axis.y) +  joint->axis.z*fabs(joint->axis.z));
00074       ROS_DEBUG("Joint axis: %d, %f, %f, %f",6-num_joints,joint->axis.x,joint->axis.y,joint->axis.z);
00075       if(joint->type != urdf::Joint::CONTINUOUS)
00076       {
00077         if (joint->safety)
00078         {
00079           min_angles_.push_back(joint->safety->soft_lower_limit);
00080           max_angles_.push_back(joint->safety->soft_upper_limit);
00081         }
00082         else
00083         {
00084           if (joint->limits)
00085           {
00086             min_angles_.push_back(joint->limits->lower);
00087             max_angles_.push_back(joint->limits->upper);
00088           }
00089           else
00090           {
00091             min_angles_.push_back(0.0);
00092             max_angles_.push_back(0.0);
00093             ROS_WARN("No joint limits or joint '%s'",joint->name.c_str());
00094           }
00095         }
00096         continuous_joint_.push_back(false);
00097       }
00098       else
00099       {
00100         min_angles_.push_back(-M_PI);
00101         max_angles_.push_back(M_PI);
00102         continuous_joint_.push_back(true);
00103       }
00104       addJointToChainInfo(link->parent_joint,solver_info_);
00105       num_joints++;
00106     }
00107     link = robot_model.getLink(link->getParent()->name);
00108   }
00109 
00110   solver_info_.link_names.push_back(tip_name);
00111 
00112   //  solver_info_.link_names.push_back(tip_name);
00113   // We expect order from root to tip, so reverse the order
00114   std::reverse(angle_multipliers_.begin(),angle_multipliers_.end());
00115   std::reverse(min_angles_.begin(),min_angles_.end());
00116   std::reverse(max_angles_.begin(),max_angles_.end());
00117   std::reverse(link_offset.begin(),link_offset.end());
00118   std::reverse(solver_info_.limits.begin(),solver_info_.limits.end());
00119   std::reverse(solver_info_.joint_names.begin(),solver_info_.joint_names.end());
00120   std::reverse(solver_info_.link_names.begin(),solver_info_.link_names.end());
00121   std::reverse(continuous_joint_.begin(),continuous_joint_.end());
00122 
00123   if(num_joints != 7)
00124   {
00125     ROS_FATAL("PR2ArmIK:: Chain from %s to %s does not have 7 joints",root_name.c_str(),tip_name.c_str());
00126     return false;
00127   }
00128 
00129   torso_shoulder_offset_x_ = link_offset[0].position.x;
00130   torso_shoulder_offset_y_ = link_offset[0].position.y;
00131   torso_shoulder_offset_z_ = link_offset[0].position.z;
00132   shoulder_upperarm_offset_ = distance(link_offset[1]);
00133   upperarm_elbow_offset_ = distance(link_offset[3]);
00134   elbow_wrist_offset_ = distance(link_offset[5]);
00135   shoulder_elbow_offset_ = shoulder_upperarm_offset_ + upperarm_elbow_offset_;
00136   shoulder_wrist_offset_ = shoulder_upperarm_offset_+upperarm_elbow_offset_+elbow_wrist_offset_;
00137 
00138   Eigen::Matrix4f home = Eigen::Matrix4f::Identity();
00139   home(0,3) = shoulder_upperarm_offset_ +  upperarm_elbow_offset_ +  elbow_wrist_offset_;
00140   home_inv_ = home.inverse();
00141   grhs_ = home;
00142   gf_ = home_inv_;
00143   solution_.resize( NUM_JOINTS_ARM7DOF);
00144   return true;
00145 }
00146 
00147 void PR2ArmIK::addJointToChainInfo(boost::shared_ptr<const urdf::Joint> joint, moveit_msgs::KinematicSolverInfo &info)
00148 {
00149   moveit_msgs::JointLimits limit;
00150   info.joint_names.push_back(joint->name);//Joints are coming in reverse order
00151 
00152   if(joint->type != urdf::Joint::CONTINUOUS)
00153   {
00154     if (joint->safety)
00155     {
00156       limit.min_position = joint->safety->soft_lower_limit;
00157       limit.max_position = joint->safety->soft_upper_limit;
00158       limit.has_position_limits = true;
00159     }
00160     else
00161       if (joint->limits)
00162       {
00163         limit.min_position = joint->limits->lower;
00164         limit.max_position = joint->limits->upper;
00165         limit.has_position_limits = true;
00166       }
00167       else
00168         limit.has_position_limits = false;
00169   }
00170   else
00171   {
00172     limit.min_position = -M_PI;
00173     limit.max_position = M_PI;
00174     limit.has_position_limits = false;
00175   }
00176   if (joint->limits)
00177   {
00178     limit.max_velocity = joint->limits->velocity;
00179     limit.has_velocity_limits = 1;
00180   }
00181   else
00182     limit.has_velocity_limits = 0;
00183   info.limits.push_back(limit);
00184 }
00185 
00186 void PR2ArmIK::getSolverInfo(moveit_msgs::KinematicSolverInfo &info)
00187 {
00188   info = solver_info_;
00189 }
00190 
00191 
00192 void PR2ArmIK::computeIKShoulderPan(const Eigen::Matrix4f &g_in, const double &t1_in, std::vector<std::vector<double> > &solution) const
00193 {
00194 //t1 = shoulder/turret pan is specified
00195 //  solution_ik_.resize(0);
00196   std::vector<double> solution_ik(NUM_JOINTS_ARM7DOF,0.0);
00197   Eigen::Matrix4f g = g_in;
00198   Eigen::Matrix4f gf_local = home_inv_;
00199   Eigen::Matrix4f grhs_local = home_inv_;
00200 //First bring everything into the arm frame
00201   g(0,3) = g_in(0,3) - torso_shoulder_offset_x_;
00202   g(1,3) = g_in(1,3) - torso_shoulder_offset_y_;
00203   g(2,3) = g_in(2,3) - torso_shoulder_offset_z_;
00204 
00205   double t1 = angles::normalize_angle(t1_in);
00206   if(!checkJointLimits(t1,0))
00207     return;
00208 
00209 
00210   double cost1, cost2, cost3, cost4;
00211   double sint1, sint2, sint3, sint4;
00212 
00213   gf_local = g*home_inv_;
00214 
00215   cost1 = cos(t1);
00216   sint1 = sin(t1);
00217 
00218   double t2(0), t3(0), t4(0), t5(0), t6(0), t7(0);
00219 
00220   double at(0), bt(0), ct(0);
00221 
00222   double theta2[2],theta3[2],theta4[2],theta5[2],theta6[4],theta7[2];
00223 
00224   double sopx = shoulder_upperarm_offset_*cost1;
00225   double sopy = shoulder_upperarm_offset_*sint1;
00226   double sopz = 0;
00227 
00228   double x = g(0,3);
00229   double y = g(1,3);
00230   double z = g(2,3);
00231 
00232   double dx = x - sopx;
00233   double dy = y - sopy;
00234   double dz = z - sopz;
00235 
00236   double dd = dx*dx + dy*dy + dz*dz;
00237 
00238   double numerator = dd-shoulder_upperarm_offset_*shoulder_upperarm_offset_+2*shoulder_upperarm_offset_*shoulder_elbow_offset_-2*shoulder_elbow_offset_*shoulder_elbow_offset_+2*shoulder_elbow_offset_*shoulder_wrist_offset_-shoulder_wrist_offset_*shoulder_wrist_offset_;
00239   double denominator = 2*(shoulder_upperarm_offset_-shoulder_elbow_offset_)*(shoulder_elbow_offset_-shoulder_wrist_offset_);
00240 
00241   double acosTerm = numerator/denominator;
00242 
00243   if (acosTerm > 1.0 || acosTerm < -1.0)
00244     return;
00245 
00246   double acos_angle = acos(acosTerm);
00247 
00248   theta4[0] = acos_angle;
00249   theta4[1] = -acos_angle;
00250 
00251 #ifdef DEBUG
00252   std::cout << "ComputeIK::theta3:" << numerator << "," << denominator << "," << std::endl << theta4[0] << std::endl;
00253 #endif
00254 
00255   for(int jj =0; jj < 2; jj++)
00256   {
00257     t4 = theta4[jj];
00258     cost4 = cos(t4);
00259     sint4 = sin(t4);
00260 
00261 #ifdef DEBUG
00262     std::cout << "t4 " << t4 << std::endl;
00263 #endif
00264     if(std::isnan(t4))
00265       continue;
00266 
00267     if(!checkJointLimits(t4,3))
00268       continue;
00269 
00270     at = x*cost1+y*sint1-shoulder_upperarm_offset_;
00271     bt = -z;
00272     ct = -shoulder_upperarm_offset_ + shoulder_elbow_offset_ + (shoulder_wrist_offset_-shoulder_elbow_offset_)*cos(t4);
00273 
00274     if(!solveCosineEqn(at,bt,ct,theta2[0],theta2[1]))
00275       continue;
00276 
00277     for(int ii=0; ii < 2; ii++)
00278     {
00279       t2 = theta2[ii];
00280       if(!checkJointLimits(t2,1))
00281         continue;
00282 
00283 
00284 #ifdef DEBUG
00285       std::cout << "t2 " << t2 << std::endl;
00286 #endif
00287       sint2 = sin(t2);
00288       cost2 = cos(t2);
00289 
00290       at = sint1*(shoulder_elbow_offset_ - shoulder_wrist_offset_)*sint2*sint4;
00291       bt = (-shoulder_elbow_offset_+shoulder_wrist_offset_)*cost1*sint4;
00292       ct = y - (shoulder_upperarm_offset_+cost2*(-shoulder_upperarm_offset_+shoulder_elbow_offset_+(-shoulder_elbow_offset_+shoulder_wrist_offset_)*cos(t4)))*sint1;
00293       if(!solveCosineEqn(at,bt,ct,theta3[0],theta3[1]))
00294         continue;
00295 
00296       for(int kk =0; kk < 2; kk++)
00297       {
00298         t3 = theta3[kk];
00299 
00300         if(!checkJointLimits(angles::normalize_angle(t3),2))
00301           continue;
00302 
00303         sint3 = sin(t3);
00304         cost3 = cos(t3);
00305 #ifdef DEBUG
00306         std::cout << "t3 " << t3 << std::endl;
00307 #endif
00308         if(fabs((shoulder_upperarm_offset_-shoulder_elbow_offset_+(shoulder_elbow_offset_-shoulder_wrist_offset_)*cost4)*sint2+(shoulder_elbow_offset_-shoulder_wrist_offset_)*cost2*cost3*sint4-z) > IK_EPS )
00309           continue;
00310 
00311         if(fabs((shoulder_elbow_offset_-shoulder_wrist_offset_)*sint1*sint3*sint4+cost1*(shoulder_upperarm_offset_+cost2*(-shoulder_upperarm_offset_+shoulder_elbow_offset_+(-shoulder_elbow_offset_+shoulder_wrist_offset_)*cost4)+(shoulder_elbow_offset_-shoulder_wrist_offset_)*cost3*sint2*sint4) - x) > IK_EPS)
00312           continue;
00313 
00314         grhs_local(0,0) = cost4*(gf_local(0,0)*cost1*cost2+gf_local(1,0)*cost2*sint1-gf_local(2,0)*sint2)-(gf_local(2,0)*cost2*cost3 + cost3*(gf_local(0,0)*cost1 + gf_local(1,0)*sint1)*sint2 + (-(gf_local(1,0)*cost1) + gf_local(0,0)*sint1)*sint3)*sint4;
00315 
00316         grhs_local(0,1) = cost4*(gf_local(0,1)*cost1*cost2 + gf_local(1,1)*cost2*sint1 - gf_local(2,1)*sint2) - (gf_local(2,1)*cost2*cost3 + cost3*(gf_local(0,1)*cost1 + gf_local(1,1)*sint1)*sint2 + (-(gf_local(1,1)*cost1) + gf_local(0,1)*sint1)*sint3)*sint4;
00317 
00318         grhs_local(0,2) = cost4*(gf_local(0,2)*cost1*cost2 + gf_local(1,2)*cost2*sint1 - gf_local(2,2)*sint2) - (gf_local(2,2)*cost2*cost3 + cost3*(gf_local(0,2)*cost1 + gf_local(1,2)*sint1)*sint2 + (-(gf_local(1,2)*cost1) + gf_local(0,2)*sint1)*sint3)*sint4;
00319 
00320         grhs_local(1,0) = cost3*(gf_local(1,0)*cost1 - gf_local(0,0)*sint1) + gf_local(2,0)*cost2*sint3 + (gf_local(0,0)*cost1 + gf_local(1,0)*sint1)*sint2*sint3;
00321 
00322         grhs_local(1,1) = cost3*(gf_local(1,1)*cost1 - gf_local(0,1)*sint1) + gf_local(2,1)*cost2*sint3 + (gf_local(0,1)*cost1 + gf_local(1,1)*sint1)*sint2*sint3;
00323 
00324         grhs_local(1,2) = cost3*(gf_local(1,2)*cost1 - gf_local(0,2)*sint1) + gf_local(2,2)*cost2*sint3 + (gf_local(0,2)*cost1 + gf_local(1,2)*sint1)*sint2*sint3;
00325 
00326         grhs_local(2,0) = cost4*(gf_local(2,0)*cost2*cost3 + cost3*(gf_local(0,0)*cost1 + gf_local(1,0)*sint1)*sint2 + (-(gf_local(1,0)*cost1) + gf_local(0,0)*sint1)*sint3) + (gf_local(0,0)*cost1*cost2 + gf_local(1,0)*cost2*sint1 - gf_local(2,0)*sint2)*sint4;
00327 
00328         grhs_local(2,1) = cost4*(gf_local(2,1)*cost2*cost3 + cost3*(gf_local(0,1)*cost1 + gf_local(1,1)*sint1)*sint2 + (-(gf_local(1,1)*cost1) + gf_local(0,1)*sint1)*sint3) + (gf_local(0,1)*cost1*cost2 + gf_local(1,1)*cost2*sint1 - gf_local(2,1)*sint2)*sint4;
00329 
00330         grhs_local(2,2) = cost4*(gf_local(2,2)*cost2*cost3 + cost3*(gf_local(0,2)*cost1 + gf_local(1,2)*sint1)*sint2 + (-(gf_local(1,2)*cost1) + gf_local(0,2)*sint1)*sint3) + (gf_local(0,2)*cost1*cost2 + gf_local(1,2)*cost2*sint1 - gf_local(2,2)*sint2)*sint4;
00331 
00332 
00333         double val1 = sqrt(grhs_local(0,1)*grhs_local(0,1)+grhs_local(0,2)*grhs_local(0,2));
00334         double val2 = grhs_local(0,0);
00335 
00336         theta6[0] = atan2(val1,val2);
00337         theta6[1] = atan2(-val1,val2);
00338 
00339 //            theta6[3] = M_PI + theta6[0];
00340 //            theta6[4] = M_PI + theta6[1];
00341 
00342         for(int mm = 0; mm < 2; mm++)
00343         {
00344           t6 = theta6[mm];
00345           if(!checkJointLimits(angles::normalize_angle(t6),5))
00346             continue;
00347 
00348 #ifdef DEBUG
00349           std::cout << "t6 " << t6 << std::endl;
00350 #endif
00351           if(fabs(cos(t6) - grhs_local(0,0)) > IK_EPS)
00352             continue;
00353 
00354           if(fabs(sin(t6)) < IK_EPS)
00355           {
00356             //                std::cout << "Singularity" << std::endl;
00357             theta5[0] = acos(grhs_local(1,1))/2.0;
00358             theta7[0] = theta7[0];
00359             theta7[1] = M_PI+theta7[0];
00360             theta5[1] = theta7[1];
00361           }
00362           else
00363           {
00364             theta7[0] = atan2(grhs_local(0,1),grhs_local(0,2));
00365             theta5[0] = atan2(grhs_local(1,0),-grhs_local(2,0));
00366             theta7[1] = M_PI+theta7[0];
00367             theta5[1] = M_PI+theta5[0];
00368           }
00369 #ifdef DEBUG
00370           std::cout << "theta1: " << t1 << std::endl;
00371           std::cout << "theta2: " << t2 << std::endl;
00372           std::cout << "theta3: " << t3 << std::endl;
00373           std::cout << "theta4: " << t4 << std::endl;
00374           std::cout << "theta5: " << t5 << std::endl;
00375           std::cout << "theta6: " << t6 << std::endl;
00376           std::cout << "theta7: " << t7 << std::endl << std::endl << std::endl;
00377 #endif
00378           for(int lll =0; lll < 2; lll++)
00379           {
00380             t5 = theta5[lll];
00381             t7 = theta7[lll];
00382             if(!checkJointLimits(t5,4))
00383               continue;
00384             if(!checkJointLimits(t7,6))
00385               continue;
00386 
00387 #ifdef DEBUG
00388             std::cout << "t5" << t5 << std::endl;
00389             std::cout << "t7" << t7 << std::endl;
00390 #endif
00391             if(fabs(sin(t6)*sin(t7)-grhs_local(0,1)) > IK_EPS || fabs(cos(t7)*sin(t6)-grhs_local(0,2)) > IK_EPS)
00392               continue;
00393 
00394             solution_ik[0] = normalize_angle(t1)*angle_multipliers_[0];
00395             solution_ik[1] = normalize_angle(t2)*angle_multipliers_[1];
00396             solution_ik[2] = normalize_angle(t3)*angle_multipliers_[2];
00397             solution_ik[3] = normalize_angle(t4)*angle_multipliers_[3];
00398             solution_ik[4] = normalize_angle(t5)*angle_multipliers_[4];
00399             solution_ik[5] = normalize_angle(t6)*angle_multipliers_[5];
00400             solution_ik[6] = normalize_angle(t7)*angle_multipliers_[6];
00401             solution.push_back(solution_ik);
00402 
00403 #ifdef DEBUG
00404             std::cout << "SOLN " << solution_ik[0] << " " << solution_ik[1] << " " <<  solution_ik[2] << " " << solution_ik[3] <<  " " << solution_ik[4] << " " << solution_ik[5] <<  " " << solution_ik[6] << std::endl << std::endl;
00405 #endif
00406           }
00407         }
00408       }
00409     }
00410   }
00411 }
00412 
00413 
00414 void PR2ArmIK::computeIKShoulderRoll(const Eigen::Matrix4f &g_in, const double &t3, std::vector<std::vector<double> > &solution) const
00415 {
00416   std::vector<double> solution_ik(NUM_JOINTS_ARM7DOF,0.0);
00417   //  ROS_INFO(" ");
00418   // solution_ik_.clear();
00419   //  ROS_INFO("Solution IK size: %d",solution_ik_.size());
00420   //  for(unsigned int i=0; i < solution_ik_.size(); i++)
00421   //  {
00422   //    solution_ik_[i].clear();
00423   //  }
00424   //  if(!solution_ik_.empty())
00425   //    solution_ik_.resize(0);
00426 //t3 = shoulder/turret roll is specified
00427   Eigen::Matrix4f g = g_in;
00428   Eigen::Matrix4f gf_local = home_inv_;
00429   Eigen::Matrix4f grhs_local = home_inv_;
00430 //First bring everything into the arm frame
00431   g(0,3) = g_in(0,3) - torso_shoulder_offset_x_;
00432   g(1,3) = g_in(1,3) - torso_shoulder_offset_y_;
00433   g(2,3) = g_in(2,3) - torso_shoulder_offset_z_;
00434 
00435   if(!checkJointLimits(t3,2))
00436   {
00437     return;
00438   }
00439   double x = g(0,3);
00440   double y = g(1,3);
00441   double z = g(2,3);
00442   double cost1, cost2, cost3, cost4;
00443   double sint1, sint2, sint3, sint4;
00444 
00445   gf_local = g*home_inv_;
00446 
00447   cost3 = cos(t3);
00448   sint3 = sin(t3);
00449 
00450   double t1(0), t2(0), t4(0), t5(0), t6(0), t7(0);
00451 
00452   double at(0), bt(0), ct(0);
00453 
00454   double theta1[2],theta2[2],theta4[4],theta5[2],theta6[4],theta7[2];
00455 
00456   double c0 = -sin(-t3)*elbow_wrist_offset_;
00457   double c1 = -cos(-t3)*elbow_wrist_offset_;
00458 
00459   double d0 = 4*shoulder_upperarm_offset_*shoulder_upperarm_offset_*(upperarm_elbow_offset_*upperarm_elbow_offset_+c1*c1-z*z);
00460   double d1 = 8*shoulder_upperarm_offset_*shoulder_upperarm_offset_*upperarm_elbow_offset_*elbow_wrist_offset_;
00461   double d2 = 4*shoulder_upperarm_offset_*shoulder_upperarm_offset_*(elbow_wrist_offset_*elbow_wrist_offset_-c1*c1);
00462 
00463   double b0 = x*x+y*y+z*z-shoulder_upperarm_offset_*shoulder_upperarm_offset_-upperarm_elbow_offset_*upperarm_elbow_offset_-c0*c0-c1*c1;
00464   double b1 = -2*upperarm_elbow_offset_*elbow_wrist_offset_;
00465 
00466   if(!solveQuadratic(b1*b1-d2,2*b0*b1-d1,b0*b0-d0,&theta4[0],&theta4[1]))
00467   {
00468 #ifdef DEBUG
00469     printf("No solution to quadratic eqn\n");
00470 #endif
00471     return;
00472   }
00473   theta4[0] = acos(theta4[0]);
00474   theta4[2] = acos(theta4[1]);
00475   theta4[1] = -theta4[0];
00476   theta4[3] = -theta4[2];
00477 
00478   for(int jj = 0; jj < 4; jj++)
00479   {
00480     t4 = theta4[jj];
00481 
00482     if(!checkJointLimits(t4,3))
00483     {
00484       continue;
00485     }
00486     cost4 = cos(t4);
00487     sint4 = sin(t4);
00488 #ifdef DEBUG
00489     std::cout << "t4 " << t4 << std::endl;
00490 #endif
00491     if(std::isnan(t4))
00492       continue;
00493     at = cos(t3)*sin(t4)*(shoulder_elbow_offset_-shoulder_wrist_offset_);
00494     bt = (shoulder_upperarm_offset_-shoulder_elbow_offset_+(shoulder_elbow_offset_-shoulder_wrist_offset_)*cos(t4));
00495     ct = z;
00496 
00497     if(!solveCosineEqn(at,bt,ct,theta2[0],theta2[1]))
00498       continue;
00499 
00500     for(int ii=0; ii < 2; ii++)
00501     {
00502       t2 = theta2[ii];
00503 #ifdef DEBUG
00504       std::cout << "t2 " << t2 << std::endl;
00505 #endif
00506       if(!checkJointLimits(t2,1))
00507       {
00508         continue;
00509       }
00510 
00511 
00512       sint2 = sin(t2);
00513       cost2 = cos(t2);
00514 
00515       at = -y;
00516       bt = x;
00517       ct = (shoulder_elbow_offset_-shoulder_wrist_offset_)*sin(t3)*sin(t4);
00518       if(!solveCosineEqn(at,bt,ct,theta1[0],theta1[1]))
00519       {
00520 #ifdef DEBUG
00521         std::cout << "could not solve cosine equation for t1" << std::endl;
00522 #endif
00523         continue;
00524       }
00525 
00526       for(int kk =0; kk < 2; kk++)
00527       {
00528         t1 = theta1[kk];
00529 #ifdef DEBUG
00530         std::cout << "t1 " << t1 << std::endl;
00531 #endif
00532         if(!checkJointLimits(t1,0))
00533         {
00534           continue;
00535         }
00536         sint1 = sin(t1);
00537         cost1 = cos(t1);
00538         if(fabs((shoulder_upperarm_offset_-shoulder_elbow_offset_+(shoulder_elbow_offset_-shoulder_wrist_offset_)*cost4)*sint2+(shoulder_elbow_offset_-shoulder_wrist_offset_)*cost2*cost3*sint4-z) > IK_EPS )
00539         {
00540 #ifdef DEBUG
00541           printf("z value not matched %f\n",fabs((shoulder_upperarm_offset_-shoulder_elbow_offset_+(shoulder_elbow_offset_-shoulder_wrist_offset_)*cost4)*sint2+(shoulder_elbow_offset_-shoulder_wrist_offset_)*cost2*cost3*sint4-z));
00542 #endif
00543           continue;
00544         }
00545         if(fabs((shoulder_elbow_offset_-shoulder_wrist_offset_)*sint1*sint3*sint4+cost1*(shoulder_upperarm_offset_+cost2*(-shoulder_upperarm_offset_+shoulder_elbow_offset_+(-shoulder_elbow_offset_+shoulder_wrist_offset_)*cost4)+(shoulder_elbow_offset_-shoulder_wrist_offset_)*cost3*sint2*sint4) - x) > IK_EPS)
00546         {
00547 #ifdef DEBUG
00548           printf("x value not matched by %f\n",fabs((shoulder_elbow_offset_-shoulder_wrist_offset_)*sint1*sint3*sint4+cost1*(shoulder_upperarm_offset_+cost2*(-shoulder_upperarm_offset_+shoulder_elbow_offset_+(-shoulder_elbow_offset_+shoulder_wrist_offset_)*cost4)+(shoulder_elbow_offset_-shoulder_wrist_offset_)*cost3*sint2*sint4) - x));
00549 #endif
00550           continue;
00551         }
00552         if(fabs(-(shoulder_elbow_offset_-shoulder_wrist_offset_)*cost1*sint3*sint4+sint1*(shoulder_upperarm_offset_+cost2*(-shoulder_upperarm_offset_+shoulder_elbow_offset_+(-shoulder_elbow_offset_+shoulder_wrist_offset_)*cost4)+(shoulder_elbow_offset_-shoulder_wrist_offset_)*cost3*sint2*sint4) - y) > IK_EPS)
00553         {
00554 #ifdef DEBUG
00555           printf("y value not matched\n");
00556 #endif
00557           continue;
00558         }
00559         grhs_local(0,0) = cost4*(gf_local(0,0)*cost1*cost2+gf_local(1,0)*cost2*sint1-gf_local(2,0)*sint2)-(gf_local(2,0)*cost2*cost3 + cost3*(gf_local(0,0)*cost1 + gf_local(1,0)*sint1)*sint2 + (-(gf_local(1,0)*cost1) + gf_local(0,0)*sint1)*sint3)*sint4;
00560 
00561         grhs_local(0,1) = cost4*(gf_local(0,1)*cost1*cost2 + gf_local(1,1)*cost2*sint1 - gf_local(2,1)*sint2) - (gf_local(2,1)*cost2*cost3 + cost3*(gf_local(0,1)*cost1 + gf_local(1,1)*sint1)*sint2 + (-(gf_local(1,1)*cost1) + gf_local(0,1)*sint1)*sint3)*sint4;
00562 
00563         grhs_local(0,2) = cost4*(gf_local(0,2)*cost1*cost2 + gf_local(1,2)*cost2*sint1 - gf_local(2,2)*sint2) - (gf_local(2,2)*cost2*cost3 + cost3*(gf_local(0,2)*cost1 + gf_local(1,2)*sint1)*sint2 + (-(gf_local(1,2)*cost1) + gf_local(0,2)*sint1)*sint3)*sint4;
00564 
00565         grhs_local(1,0) = cost3*(gf_local(1,0)*cost1 - gf_local(0,0)*sint1) + gf_local(2,0)*cost2*sint3 + (gf_local(0,0)*cost1 + gf_local(1,0)*sint1)*sint2*sint3;
00566 
00567         grhs_local(1,1) = cost3*(gf_local(1,1)*cost1 - gf_local(0,1)*sint1) + gf_local(2,1)*cost2*sint3 + (gf_local(0,1)*cost1 + gf_local(1,1)*sint1)*sint2*sint3;
00568 
00569         grhs_local(1,2) = cost3*(gf_local(1,2)*cost1 - gf_local(0,2)*sint1) + gf_local(2,2)*cost2*sint3 + (gf_local(0,2)*cost1 + gf_local(1,2)*sint1)*sint2*sint3;
00570 
00571         grhs_local(2,0) = cost4*(gf_local(2,0)*cost2*cost3 + cost3*(gf_local(0,0)*cost1 + gf_local(1,0)*sint1)*sint2 + (-(gf_local(1,0)*cost1) + gf_local(0,0)*sint1)*sint3) + (gf_local(0,0)*cost1*cost2 + gf_local(1,0)*cost2*sint1 - gf_local(2,0)*sint2)*sint4;
00572 
00573         grhs_local(2,1) = cost4*(gf_local(2,1)*cost2*cost3 + cost3*(gf_local(0,1)*cost1 + gf_local(1,1)*sint1)*sint2 + (-(gf_local(1,1)*cost1) + gf_local(0,1)*sint1)*sint3) + (gf_local(0,1)*cost1*cost2 + gf_local(1,1)*cost2*sint1 - gf_local(2,1)*sint2)*sint4;
00574 
00575         grhs_local(2,2) = cost4*(gf_local(2,2)*cost2*cost3 + cost3*(gf_local(0,2)*cost1 + gf_local(1,2)*sint1)*sint2 + (-(gf_local(1,2)*cost1) + gf_local(0,2)*sint1)*sint3) + (gf_local(0,2)*cost1*cost2 + gf_local(1,2)*cost2*sint1 - gf_local(2,2)*sint2)*sint4;
00576 
00577 
00578 
00579 
00580 
00581 
00582 
00583 
00584 
00585         double val1 = sqrt(grhs_local(0,1)*grhs_local(0,1)+grhs_local(0,2)*grhs_local(0,2));
00586         double val2 = grhs_local(0,0);
00587 
00588         theta6[0] = atan2(val1,val2);
00589         theta6[1] = atan2(-val1,val2);
00590 
00591         for(int mm = 0; mm < 2; mm++)
00592         {
00593           t6 = theta6[mm];
00594 #ifdef DEBUG
00595           std::cout << "t6 " << t6 << std::endl;
00596 #endif
00597           if(!checkJointLimits(t6,5))
00598           {
00599             continue;
00600           }
00601 
00602 
00603           if(fabs(cos(t6) - grhs_local(0,0)) > IK_EPS)
00604             continue;
00605 
00606           if(fabs(sin(t6)) < IK_EPS)
00607           {
00608             //                std::cout << "Singularity" << std::endl;
00609             theta5[0] = acos(grhs_local(1,1))/2.0;
00610             theta7[0] = theta5[0];
00611 //            theta7[1] = M_PI+theta7[0];
00612 //            theta5[1] = theta7[1];
00613           }
00614           else
00615           {
00616             theta7[0] = atan2(grhs_local(0,1)/sin(t6),grhs_local(0,2)/sin(t6));
00617             theta5[0] = atan2(grhs_local(1,0)/sin(t6),-grhs_local(2,0)/sin(t6));
00618 //            theta7[1] = M_PI+theta7[0];
00619 //            theta5[1] = M_PI+theta5[0];
00620           }
00621           for(int lll =0; lll < 1; lll++)
00622           {
00623             t5 = theta5[lll];
00624             t7 = theta7[lll];
00625 
00626             if(!checkJointLimits(t5,4))
00627             {
00628               continue;
00629             }
00630             if(!checkJointLimits(t7,6))
00631             {
00632               continue;
00633             }
00634 
00635 
00636 #ifdef DEBUG
00637             std::cout << "t5 " << t5 << std::endl;
00638             std::cout << "t7 " << t7 << std::endl;
00639 #endif
00640             //           if(fabs(sin(t6)*sin(t7)-grhs_local(0,1)) > IK_EPS || fabs(cos(t7)*sin(t6)-grhs_local(0,2)) > IK_EPS)
00641             //  continue;
00642 
00643 #ifdef DEBUG
00644             std::cout << "theta1: " << t1 << std::endl;
00645             std::cout << "theta2: " << t2 << std::endl;
00646             std::cout << "theta3: " << t3 << std::endl;
00647             std::cout << "theta4: " << t4 << std::endl;
00648             std::cout << "theta5: " << t5 << std::endl;
00649             std::cout << "theta6: " << t6 << std::endl;
00650             std::cout << "theta7: " << t7 << std::endl << std::endl << std::endl;
00651 #endif
00652 
00653 
00654             solution_ik[0] = normalize_angle(t1*angle_multipliers_[0]);
00655             solution_ik[1] = normalize_angle(t2*angle_multipliers_[1]);
00656             solution_ik[2] = t3*angle_multipliers_[2];
00657             solution_ik[3] = normalize_angle(t4*angle_multipliers_[3]);
00658             solution_ik[4] = normalize_angle(t5*angle_multipliers_[4]);
00659             solution_ik[5] = normalize_angle(t6*angle_multipliers_[5]);
00660             solution_ik[6] = normalize_angle(t7*angle_multipliers_[6]);
00661             solution.push_back(solution_ik);
00662 #ifdef DEBUG
00663             std::cout << "SOLN " << solution_ik[0] << " " << solution_ik[1] << " " <<  solution_ik[2] << " " << solution_ik[3] <<  " " << solution_ik[4] << " " << solution_ik[5] <<  " " << solution_ik[6] << std::endl << std::endl;
00664 #endif
00665           }
00666         }
00667       }
00668     }
00669   }
00670 }
00671 
00672 
00673 bool PR2ArmIK::checkJointLimits(const std::vector<double> &joint_values) const
00674 {
00675   for(int i=0; i<NUM_JOINTS_ARM7DOF; i++)
00676   {
00677     if(!checkJointLimits(angles::normalize_angle(joint_values[i]*angle_multipliers_[i]),i))
00678     {
00679       return false;
00680     }
00681   }
00682   return true;
00683 }
00684 
00685 bool  PR2ArmIK::checkJointLimits(const double &joint_value, const int &joint_num) const
00686 {
00687   double jv;
00688   if(continuous_joint_[joint_num])
00689     jv= angles::normalize_angle(joint_value*angle_multipliers_[joint_num]);
00690   else if (joint_num ==2)
00691     jv = joint_value*angle_multipliers_[joint_num];
00692   else
00693     jv= angles::normalize_angle(joint_value*angle_multipliers_[joint_num]);
00694 
00695   if(jv < min_angles_[joint_num] || jv > max_angles_[joint_num])
00696   {
00697     // ROS_INFO("Angle %d = %f out of range: (%f,%f)\n",joint_num,joint_value,min_angles_[joint_num],max_angles_[joint_num]);
00698     return false;
00699   }
00700   return true;
00701 }


pr2_moveit_plugins
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 11:14:04