56 bool PR2ArmIK::init(
const urdf::ModelInterface& 
robot_model, 
const std::string& root_name, 
const std::string& tip_name)
 
   58   std::vector<urdf::Pose> link_offset;
 
   60   urdf::LinkConstSharedPtr link = 
robot_model.getLink(tip_name);
 
   61   while (link && num_joints < 7)
 
   63     urdf::JointConstSharedPtr joint;
 
   64     if (link->parent_joint)
 
   65       joint = 
robot_model.getJoint(link->parent_joint->name);
 
   68       if (link->parent_joint)
 
   69         ROS_ERROR_NAMED(
"pr2_arm_kinematics_plugin", 
"Could not find joint: %s", link->parent_joint->name.c_str());
 
   71         ROS_ERROR_NAMED(
"pr2_arm_kinematics_plugin", 
"Link %s has no parent joint", link->name.c_str());
 
   74     if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
 
   76       link_offset.push_back(link->parent_joint->parent_to_joint_origin_transform);
 
   77       angle_multipliers_.push_back(joint->axis.x * fabs(joint->axis.x) + joint->axis.y * fabs(joint->axis.y) +
 
   78                                    joint->axis.z * fabs(joint->axis.z));
 
   79       ROS_DEBUG_NAMED(
"pr2_arm_kinematics_plugin", 
"Joint axis: %d, %f, %f, %f", 6 - num_joints, joint->axis.x,
 
   80                       joint->axis.y, joint->axis.z);
 
   81       if (joint->type != urdf::Joint::CONTINUOUS)
 
   85           min_angles_.push_back(joint->safety->soft_lower_limit);
 
   86           max_angles_.push_back(joint->safety->soft_upper_limit);
 
   92             min_angles_.push_back(joint->limits->lower);
 
   93             max_angles_.push_back(joint->limits->upper);
 
   97             min_angles_.push_back(0.0);
 
   98             max_angles_.push_back(0.0);
 
   99             ROS_WARN_NAMED(
"pr2_arm_kinematics_plugin", 
"No joint limits or joint '%s'", joint->name.c_str());
 
  102         continuous_joint_.push_back(
false);
 
  106         min_angles_.push_back(-
M_PI);
 
  107         max_angles_.push_back(
M_PI);
 
  108         continuous_joint_.push_back(
true);
 
  110       addJointToChainInfo(link->parent_joint, solver_info_);
 
  113     link = 
robot_model.getLink(link->getParent()->name);
 
  116   solver_info_.link_names.push_back(tip_name);
 
  120   std::reverse(angle_multipliers_.begin(), angle_multipliers_.end());
 
  121   std::reverse(min_angles_.begin(), min_angles_.end());
 
  122   std::reverse(max_angles_.begin(), max_angles_.end());
 
  123   std::reverse(link_offset.begin(), link_offset.end());
 
  124   std::reverse(solver_info_.limits.begin(), solver_info_.limits.end());
 
  125   std::reverse(solver_info_.joint_names.begin(), solver_info_.joint_names.end());
 
  126   std::reverse(solver_info_.link_names.begin(), solver_info_.link_names.end());
 
  127   std::reverse(continuous_joint_.begin(), continuous_joint_.end());
 
  131     ROS_ERROR_NAMED(
"pr2_arm_kinematics_plugin", 
"PR2ArmIK:: Chain from %s to %s does not have 7 joints",
 
  132                     root_name.c_str(), tip_name.c_str());
 
  136   torso_shoulder_offset_x_ = link_offset[0].position.x;
 
  137   torso_shoulder_offset_y_ = link_offset[0].position.y;
 
  138   torso_shoulder_offset_z_ = link_offset[0].position.z;
 
  139   shoulder_upperarm_offset_ = 
distance(link_offset[1]);
 
  140   upperarm_elbow_offset_ = 
distance(link_offset[3]);
 
  141   elbow_wrist_offset_ = 
distance(link_offset[5]);
 
  142   shoulder_elbow_offset_ = shoulder_upperarm_offset_ + upperarm_elbow_offset_;
 
  143   shoulder_wrist_offset_ = shoulder_upperarm_offset_ + upperarm_elbow_offset_ + elbow_wrist_offset_;
 
  145   Eigen::Isometry3f home = Eigen::Isometry3f::Identity();
 
  146   home(0, 3) = shoulder_upperarm_offset_ + upperarm_elbow_offset_ + elbow_wrist_offset_;
 
  147   home_inv_ = home.inverse();
 
  154 void PR2ArmIK::addJointToChainInfo(
const urdf::JointConstSharedPtr& joint, moveit_msgs::KinematicSolverInfo& info)
 
  156   moveit_msgs::JointLimits limit;
 
  157   info.joint_names.push_back(joint->name);  
 
  159   if (joint->type != urdf::Joint::CONTINUOUS)
 
  163       limit.min_position = joint->safety->soft_lower_limit;
 
  164       limit.max_position = joint->safety->soft_upper_limit;
 
  165       limit.has_position_limits = 
true;
 
  167     else if (joint->limits)
 
  169       limit.min_position = joint->limits->lower;
 
  170       limit.max_position = joint->limits->upper;
 
  171       limit.has_position_limits = 
true;
 
  174       limit.has_position_limits = 
false;
 
  178     limit.min_position = -
M_PI;
 
  179     limit.max_position = 
M_PI;
 
  180     limit.has_position_limits = 
false;
 
  184     limit.max_velocity = joint->limits->velocity;
 
  185     limit.has_velocity_limits = 1;
 
  188     limit.has_velocity_limits = 0;
 
  189   info.limits.push_back(limit);
 
  192 void PR2ArmIK::getSolverInfo(moveit_msgs::KinematicSolverInfo& info)
 
  197 void PR2ArmIK::computeIKShoulderPan(
const Eigen::Isometry3f& g_in, 
const double& t1_in,
 
  198                                     std::vector<std::vector<double> >& solution)
 const 
  203   Eigen::Isometry3f g = g_in;
 
  204   Eigen::Isometry3f gf_local = home_inv_;
 
  205   Eigen::Isometry3f grhs_local = home_inv_;
 
  207   g(0, 3) = g_in(0, 3) - torso_shoulder_offset_x_;
 
  208   g(1, 3) = g_in(1, 3) - torso_shoulder_offset_y_;
 
  209   g(2, 3) = g_in(2, 3) - torso_shoulder_offset_z_;
 
  212   if (!checkJointLimits(t1, 0))
 
  215   double cost1, cost2, cost3, cost4;
 
  216   double sint1, sint2, sint3, sint4;
 
  218   gf_local = g * home_inv_;
 
  223   double t2(0), t3(0), t4(0), t5(0), t6(0), t7(0);
 
  225   double at(0), bt(0), ct(0);
 
  227   double theta2[2], theta3[2], theta4[2], theta5[2], theta6[4], theta7[2];
 
  229   double sopx = shoulder_upperarm_offset_ * cost1;
 
  230   double sopy = shoulder_upperarm_offset_ * sint1;
 
  237   double dx = 
x - sopx;
 
  238   double dy = 
y - sopy;
 
  239   double dz = 
z - sopz;
 
  241   double dd = dx * dx + dy * dy + dz * dz;
 
  244       dd - shoulder_upperarm_offset_ * shoulder_upperarm_offset_ +
 
  245       2 * shoulder_upperarm_offset_ * shoulder_elbow_offset_ - 2 * shoulder_elbow_offset_ * shoulder_elbow_offset_ +
 
  246       2 * shoulder_elbow_offset_ * shoulder_wrist_offset_ - shoulder_wrist_offset_ * shoulder_wrist_offset_;
 
  248       2 * (shoulder_upperarm_offset_ - shoulder_elbow_offset_) * (shoulder_elbow_offset_ - shoulder_wrist_offset_);
 
  250   double acos_term = numerator / denominator;
 
  252   if (acos_term > 1.0 || acos_term < -1.0)
 
  255   double acos_angle = acos(acos_term);
 
  257   theta4[0] = acos_angle;
 
  258   theta4[1] = -acos_angle;
 
  261   std::cout << 
"ComputeIK::theta3:" << numerator << 
"," << denominator << 
"," << std::endl << theta4[0] << std::endl;
 
  264   for (
double theta : theta4)
 
  271     std::cout << 
"t4 " << t4 << std::endl;
 
  276     if (!checkJointLimits(t4, 3))
 
  279     at = 
x * cost1 + 
y * sint1 - shoulder_upperarm_offset_;
 
  281     ct = -shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
 
  282          (shoulder_wrist_offset_ - shoulder_elbow_offset_) * cos(t4);
 
  287     for (
double theta : theta2)
 
  290       if (!checkJointLimits(t2, 1))
 
  294       std::cout << 
"t2 " << t2 << std::endl;
 
  299       at = sint1 * (shoulder_elbow_offset_ - shoulder_wrist_offset_) * sint2 * sint4;
 
  300       bt = (-shoulder_elbow_offset_ + shoulder_wrist_offset_) * cost1 * sint4;
 
  301       ct = 
y - (shoulder_upperarm_offset_ + cost2 * (-shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
 
  302                                                      (-shoulder_elbow_offset_ + shoulder_wrist_offset_) * cos(t4))) *
 
  307       for (
double theta : theta3)
 
  317         std::cout << 
"t3 " << t3 << std::endl;
 
  319         if (fabs((shoulder_upperarm_offset_ - shoulder_elbow_offset_ +
 
  320                   (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost4) *
 
  322                  (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost2 * cost3 * sint4 - 
z) > 
IK_EPS)
 
  325         if (fabs((shoulder_elbow_offset_ - shoulder_wrist_offset_) * sint1 * sint3 * sint4 +
 
  326                  cost1 * (shoulder_upperarm_offset_ +
 
  327                           cost2 * (-shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
 
  328                                    (-shoulder_elbow_offset_ + shoulder_wrist_offset_) * cost4) +
 
  329                           (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost3 * sint2 * sint4) -
 
  334             cost4 * (gf_local(0, 0) * cost1 * cost2 + gf_local(1, 0) * cost2 * sint1 - gf_local(2, 0) * sint2) -
 
  335             (gf_local(2, 0) * cost2 * cost3 + cost3 * (gf_local(0, 0) * cost1 + gf_local(1, 0) * sint1) * sint2 +
 
  336              (-(gf_local(1, 0) * cost1) + gf_local(0, 0) * sint1) * sint3) *
 
  340             cost4 * (gf_local(0, 1) * cost1 * cost2 + gf_local(1, 1) * cost2 * sint1 - gf_local(2, 1) * sint2) -
 
  341             (gf_local(2, 1) * cost2 * cost3 + cost3 * (gf_local(0, 1) * cost1 + gf_local(1, 1) * sint1) * sint2 +
 
  342              (-(gf_local(1, 1) * cost1) + gf_local(0, 1) * sint1) * sint3) *
 
  346             cost4 * (gf_local(0, 2) * cost1 * cost2 + gf_local(1, 2) * cost2 * sint1 - gf_local(2, 2) * sint2) -
 
  347             (gf_local(2, 2) * cost2 * cost3 + cost3 * (gf_local(0, 2) * cost1 + gf_local(1, 2) * sint1) * sint2 +
 
  348              (-(gf_local(1, 2) * cost1) + gf_local(0, 2) * sint1) * sint3) *
 
  351         grhs_local(1, 0) = cost3 * (gf_local(1, 0) * cost1 - gf_local(0, 0) * sint1) + gf_local(2, 0) * cost2 * sint3 +
 
  352                            (gf_local(0, 0) * cost1 + gf_local(1, 0) * sint1) * sint2 * sint3;
 
  354         grhs_local(1, 1) = cost3 * (gf_local(1, 1) * cost1 - gf_local(0, 1) * sint1) + gf_local(2, 1) * cost2 * sint3 +
 
  355                            (gf_local(0, 1) * cost1 + gf_local(1, 1) * sint1) * sint2 * sint3;
 
  357         grhs_local(1, 2) = cost3 * (gf_local(1, 2) * cost1 - gf_local(0, 2) * sint1) + gf_local(2, 2) * cost2 * sint3 +
 
  358                            (gf_local(0, 2) * cost1 + gf_local(1, 2) * sint1) * sint2 * sint3;
 
  362                 (gf_local(2, 0) * cost2 * cost3 + cost3 * (gf_local(0, 0) * cost1 + gf_local(1, 0) * sint1) * sint2 +
 
  363                  (-(gf_local(1, 0) * cost1) + gf_local(0, 0) * sint1) * sint3) +
 
  364             (gf_local(0, 0) * cost1 * cost2 + gf_local(1, 0) * cost2 * sint1 - gf_local(2, 0) * sint2) * sint4;
 
  368                 (gf_local(2, 1) * cost2 * cost3 + cost3 * (gf_local(0, 1) * cost1 + gf_local(1, 1) * sint1) * sint2 +
 
  369                  (-(gf_local(1, 1) * cost1) + gf_local(0, 1) * sint1) * sint3) +
 
  370             (gf_local(0, 1) * cost1 * cost2 + gf_local(1, 1) * cost2 * sint1 - gf_local(2, 1) * sint2) * sint4;
 
  374                 (gf_local(2, 2) * cost2 * cost3 + cost3 * (gf_local(0, 2) * cost1 + gf_local(1, 2) * sint1) * sint2 +
 
  375                  (-(gf_local(1, 2) * cost1) + gf_local(0, 2) * sint1) * sint3) +
 
  376             (gf_local(0, 2) * cost1 * cost2 + gf_local(1, 2) * cost2 * sint1 - gf_local(2, 2) * sint2) * sint4;
 
  378         double val1 = sqrt(grhs_local(0, 1) * grhs_local(0, 1) + grhs_local(0, 2) * grhs_local(0, 2));
 
  379         double val2 = grhs_local(0, 0);
 
  381         theta6[0] = atan2(val1, val2);
 
  382         theta6[1] = atan2(-val1, val2);
 
  387         for (
int mm = 0; mm < 2; mm++)
 
  394           std::cout << 
"t6 " << t6 << std::endl;
 
  396           if (fabs(cos(t6) - grhs_local(0, 0)) > 
IK_EPS)
 
  399           if (fabs(sin(t6)) < 
IK_EPS)
 
  402             theta5[0] = acos(grhs_local(1, 1)) / 2.0;
 
  403             theta7[0] = theta7[0];
 
  404             theta7[1] = 
M_PI + theta7[0];
 
  405             theta5[1] = theta7[1];
 
  409             theta7[0] = atan2(grhs_local(0, 1), grhs_local(0, 2));
 
  410             theta5[0] = atan2(grhs_local(1, 0), -grhs_local(2, 0));
 
  411             theta7[1] = 
M_PI + theta7[0];
 
  412             theta5[1] = 
M_PI + theta5[0];
 
  415           std::cout << 
"theta1: " << t1 << std::endl;
 
  416           std::cout << 
"theta2: " << t2 << std::endl;
 
  417           std::cout << 
"theta3: " << t3 << std::endl;
 
  418           std::cout << 
"theta4: " << t4 << std::endl;
 
  419           std::cout << 
"theta5: " << t5 << std::endl;
 
  420           std::cout << 
"theta6: " << t6 << std::endl;
 
  421           std::cout << 
"theta7: " << t7 << std::endl << std::endl << std::endl;
 
  423           for (
int lll = 0; lll < 2; lll++)
 
  427             if (!checkJointLimits(t5, 4))
 
  429             if (!checkJointLimits(t7, 6))
 
  433             std::cout << 
"t5" << t5 << std::endl;
 
  434             std::cout << 
"t7" << t7 << std::endl;
 
  436             if (fabs(sin(t6) * sin(t7) - grhs_local(0, 1)) > 
IK_EPS ||
 
  437                 fabs(cos(t7) * sin(t6) - grhs_local(0, 2)) > 
IK_EPS)
 
  447             solution.push_back(solution_ik);
 
  450             std::cout << 
"SOLN " << solution_ik[0] << 
" " << solution_ik[1] << 
" " << solution_ik[2] << 
" " 
  451                       << solution_ik[3] << 
" " << solution_ik[4] << 
" " << solution_ik[5] << 
" " << solution_ik[6]
 
  462 void PR2ArmIK::computeIKShoulderRoll(
const Eigen::Isometry3f& g_in, 
const double& t3,
 
  463                                      std::vector<std::vector<double> >& solution)
 const 
  476   Eigen::Isometry3f g = g_in;
 
  477   Eigen::Isometry3f gf_local = home_inv_;
 
  478   Eigen::Isometry3f grhs_local = home_inv_;
 
  480   g(0, 3) = g_in(0, 3) - torso_shoulder_offset_x_;
 
  481   g(1, 3) = g_in(1, 3) - torso_shoulder_offset_y_;
 
  482   g(2, 3) = g_in(2, 3) - torso_shoulder_offset_z_;
 
  484   if (!checkJointLimits(t3, 2))
 
  491   double cost1, cost2, cost3, cost4;
 
  492   double sint1, sint2, sint3, sint4;
 
  494   gf_local = g * home_inv_;
 
  499   double t1(0), t2(0), t4(0), t5(0), t6(0), t7(0);
 
  501   double at(0), bt(0), ct(0);
 
  503   double theta1[2], theta2[2], theta4[4], theta5[2], theta6[4], theta7[2];
 
  505   double c0 = -sin(-t3) * elbow_wrist_offset_;
 
  506   double c1 = -cos(-t3) * elbow_wrist_offset_;
 
  508   double d0 = 4 * shoulder_upperarm_offset_ * shoulder_upperarm_offset_ *
 
  509               (upperarm_elbow_offset_ * upperarm_elbow_offset_ + c1 * c1 - 
z * 
z);
 
  510   double d1 = 8 * shoulder_upperarm_offset_ * shoulder_upperarm_offset_ * upperarm_elbow_offset_ * elbow_wrist_offset_;
 
  512       4 * shoulder_upperarm_offset_ * shoulder_upperarm_offset_ * (elbow_wrist_offset_ * elbow_wrist_offset_ - c1 * c1);
 
  514   double b0 = 
x * 
x + 
y * 
y + 
z * 
z - shoulder_upperarm_offset_ * shoulder_upperarm_offset_ -
 
  515               upperarm_elbow_offset_ * upperarm_elbow_offset_ - c0 * c0 - c1 * c1;
 
  516   double b1 = -2 * upperarm_elbow_offset_ * elbow_wrist_offset_;
 
  518   if (!
solveQuadratic(b1 * b1 - d2, 2 * b0 * b1 - d1, b0 * b0 - d0, &theta4[0], &theta4[1]))
 
  521     printf(
"No solution to quadratic eqn\n");
 
  525   theta4[0] = acos(theta4[0]);
 
  526   theta4[2] = acos(theta4[1]);
 
  527   theta4[1] = -theta4[0];
 
  528   theta4[3] = -theta4[2];
 
  530   for (
double theta : theta4)
 
  534     if (!checkJointLimits(t4, 3))
 
  541     std::cout << 
"t4 " << t4 << std::endl;
 
  545     at = cos(t3) * sin(t4) * (shoulder_elbow_offset_ - shoulder_wrist_offset_);
 
  546     bt = (shoulder_upperarm_offset_ - shoulder_elbow_offset_ +
 
  547           (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cos(t4));
 
  553     for (
double theta : theta2)
 
  557       std::cout << 
"t2 " << t2 << std::endl;
 
  559       if (!checkJointLimits(t2, 1))
 
  569       ct = (shoulder_elbow_offset_ - shoulder_wrist_offset_) * sin(t3) * sin(t4);
 
  573         std::cout << 
"could not solve cosine equation for t1" << std::endl;
 
  578       for (
double theta : theta1)
 
  582         std::cout << 
"t1 " << t1 << std::endl;
 
  584         if (!checkJointLimits(t1, 0))
 
  590         if (fabs((shoulder_upperarm_offset_ - shoulder_elbow_offset_ +
 
  591                   (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost4) *
 
  593                  (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost2 * cost3 * sint4 - 
z) > 
IK_EPS)
 
  596           printf(
"z value not matched %f\n",
 
  597                  fabs((shoulder_upperarm_offset_ - shoulder_elbow_offset_ +
 
  598                        (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost4) *
 
  600                       (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost2 * cost3 * sint4 - 
z));
 
  604         if (fabs((shoulder_elbow_offset_ - shoulder_wrist_offset_) * sint1 * sint3 * sint4 +
 
  605                  cost1 * (shoulder_upperarm_offset_ +
 
  606                           cost2 * (-shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
 
  607                                    (-shoulder_elbow_offset_ + shoulder_wrist_offset_) * cost4) +
 
  608                           (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost3 * sint2 * sint4) -
 
  612           printf(
"x value not matched by %f\n",
 
  613                  fabs((shoulder_elbow_offset_ - shoulder_wrist_offset_) * sint1 * sint3 * sint4 +
 
  614                       cost1 * (shoulder_upperarm_offset_ +
 
  615                                cost2 * (-shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
 
  616                                         (-shoulder_elbow_offset_ + shoulder_wrist_offset_) * cost4) +
 
  617                                (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost3 * sint2 * sint4) -
 
  622         if (fabs(-(shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost1 * sint3 * sint4 +
 
  623                  sint1 * (shoulder_upperarm_offset_ +
 
  624                           cost2 * (-shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
 
  625                                    (-shoulder_elbow_offset_ + shoulder_wrist_offset_) * cost4) +
 
  626                           (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost3 * sint2 * sint4) -
 
  630           printf(
"y value not matched\n");
 
  635             cost4 * (gf_local(0, 0) * cost1 * cost2 + gf_local(1, 0) * cost2 * sint1 - gf_local(2, 0) * sint2) -
 
  636             (gf_local(2, 0) * cost2 * cost3 + cost3 * (gf_local(0, 0) * cost1 + gf_local(1, 0) * sint1) * sint2 +
 
  637              (-(gf_local(1, 0) * cost1) + gf_local(0, 0) * sint1) * sint3) *
 
  641             cost4 * (gf_local(0, 1) * cost1 * cost2 + gf_local(1, 1) * cost2 * sint1 - gf_local(2, 1) * sint2) -
 
  642             (gf_local(2, 1) * cost2 * cost3 + cost3 * (gf_local(0, 1) * cost1 + gf_local(1, 1) * sint1) * sint2 +
 
  643              (-(gf_local(1, 1) * cost1) + gf_local(0, 1) * sint1) * sint3) *
 
  647             cost4 * (gf_local(0, 2) * cost1 * cost2 + gf_local(1, 2) * cost2 * sint1 - gf_local(2, 2) * sint2) -
 
  648             (gf_local(2, 2) * cost2 * cost3 + cost3 * (gf_local(0, 2) * cost1 + gf_local(1, 2) * sint1) * sint2 +
 
  649              (-(gf_local(1, 2) * cost1) + gf_local(0, 2) * sint1) * sint3) *
 
  652         grhs_local(1, 0) = cost3 * (gf_local(1, 0) * cost1 - gf_local(0, 0) * sint1) + gf_local(2, 0) * cost2 * sint3 +
 
  653                            (gf_local(0, 0) * cost1 + gf_local(1, 0) * sint1) * sint2 * sint3;
 
  655         grhs_local(1, 1) = cost3 * (gf_local(1, 1) * cost1 - gf_local(0, 1) * sint1) + gf_local(2, 1) * cost2 * sint3 +
 
  656                            (gf_local(0, 1) * cost1 + gf_local(1, 1) * sint1) * sint2 * sint3;
 
  658         grhs_local(1, 2) = cost3 * (gf_local(1, 2) * cost1 - gf_local(0, 2) * sint1) + gf_local(2, 2) * cost2 * sint3 +
 
  659                            (gf_local(0, 2) * cost1 + gf_local(1, 2) * sint1) * sint2 * sint3;
 
  663                 (gf_local(2, 0) * cost2 * cost3 + cost3 * (gf_local(0, 0) * cost1 + gf_local(1, 0) * sint1) * sint2 +
 
  664                  (-(gf_local(1, 0) * cost1) + gf_local(0, 0) * sint1) * sint3) +
 
  665             (gf_local(0, 0) * cost1 * cost2 + gf_local(1, 0) * cost2 * sint1 - gf_local(2, 0) * sint2) * sint4;
 
  669                 (gf_local(2, 1) * cost2 * cost3 + cost3 * (gf_local(0, 1) * cost1 + gf_local(1, 1) * sint1) * sint2 +
 
  670                  (-(gf_local(1, 1) * cost1) + gf_local(0, 1) * sint1) * sint3) +
 
  671             (gf_local(0, 1) * cost1 * cost2 + gf_local(1, 1) * cost2 * sint1 - gf_local(2, 1) * sint2) * sint4;
 
  675                 (gf_local(2, 2) * cost2 * cost3 + cost3 * (gf_local(0, 2) * cost1 + gf_local(1, 2) * sint1) * sint2 +
 
  676                  (-(gf_local(1, 2) * cost1) + gf_local(0, 2) * sint1) * sint3) +
 
  677             (gf_local(0, 2) * cost1 * cost2 + gf_local(1, 2) * cost2 * sint1 - gf_local(2, 2) * sint2) * sint4;
 
  679         double val1 = sqrt(grhs_local(0, 1) * grhs_local(0, 1) + grhs_local(0, 2) * grhs_local(0, 2));
 
  680         double val2 = grhs_local(0, 0);
 
  682         theta6[0] = atan2(val1, val2);
 
  683         theta6[1] = atan2(-val1, val2);
 
  685         for (
int mm = 0; mm < 2; mm++)
 
  689           std::cout << 
"t6 " << t6 << std::endl;
 
  691           if (!checkJointLimits(t6, 5))
 
  696           if (fabs(cos(t6) - grhs_local(0, 0)) > 
IK_EPS)
 
  699           if (fabs(sin(t6)) < 
IK_EPS)
 
  702             theta5[0] = acos(grhs_local(1, 1)) / 2.0;
 
  703             theta7[0] = theta5[0];
 
  709             theta7[0] = atan2(grhs_local(0, 1) / sin(t6), grhs_local(0, 2) / sin(t6));
 
  710             theta5[0] = atan2(grhs_local(1, 0) / sin(t6), -grhs_local(2, 0) / sin(t6));
 
  714           for (
int lll = 0; lll < 1; lll++)
 
  719             if (!checkJointLimits(t5, 4))
 
  723             if (!checkJointLimits(t7, 6))
 
  729             std::cout << 
"t5 " << t5 << std::endl;
 
  730             std::cout << 
"t7 " << t7 << std::endl;
 
  736             std::cout << 
"theta1: " << t1 << std::endl;
 
  737             std::cout << 
"theta2: " << t2 << std::endl;
 
  738             std::cout << 
"theta3: " << t3 << std::endl;
 
  739             std::cout << 
"theta4: " << t4 << std::endl;
 
  740             std::cout << 
"theta5: " << t5 << std::endl;
 
  741             std::cout << 
"theta6: " << t6 << std::endl;
 
  742             std::cout << 
"theta7: " << t7 << std::endl << std::endl << std::endl;
 
  747             solution_ik[2] = t3 * angle_multipliers_[2];
 
  752             solution.push_back(solution_ik);
 
  754             std::cout << 
"SOLN " << solution_ik[0] << 
" " << solution_ik[1] << 
" " << solution_ik[2] << 
" " 
  755                       << solution_ik[3] << 
" " << solution_ik[4] << 
" " << solution_ik[5] << 
" " << solution_ik[6]
 
  766 bool PR2ArmIK::checkJointLimits(
const std::vector<double>& joint_values)
 const 
  778 bool PR2ArmIK::checkJointLimits(
const double& joint_value, 
const int& joint_num)
 const 
  781   if (continuous_joint_[joint_num])
 
  783   else if (joint_num == 2)
 
  784     jv = joint_value * angle_multipliers_[joint_num];
 
  788   return !(jv < min_angles_[joint_num] || jv > max_angles_[joint_num]);