56 bool PR2ArmIK::init(
const urdf::Model &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(
"Could not find joint: %s",link->parent_joint->name.c_str());
71 ROS_ERROR(
"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) + joint->axis.z*fabs(joint->axis.z));
78 ROS_DEBUG(
"Joint axis: %d, %f, %f, %f",6-num_joints,joint->axis.x,joint->axis.y,joint->axis.z);
79 if(joint->type != urdf::Joint::CONTINUOUS)
83 min_angles_.push_back(joint->safety->soft_lower_limit);
84 max_angles_.push_back(joint->safety->soft_upper_limit);
90 min_angles_.push_back(joint->limits->lower);
91 max_angles_.push_back(joint->limits->upper);
95 min_angles_.push_back(0.0);
96 max_angles_.push_back(0.0);
97 ROS_WARN(
"No joint limits or joint '%s'",joint->name.c_str());
100 continuous_joint_.push_back(
false);
104 min_angles_.push_back(-M_PI);
105 max_angles_.push_back(M_PI);
106 continuous_joint_.push_back(
true);
108 addJointToChainInfo(link->parent_joint,solver_info_);
111 link = robot_model.getLink(link->getParent()->name);
114 solver_info_.link_names.push_back(tip_name);
118 std::reverse(angle_multipliers_.begin(),angle_multipliers_.end());
119 std::reverse(min_angles_.begin(),min_angles_.end());
120 std::reverse(max_angles_.begin(),max_angles_.end());
121 std::reverse(link_offset.begin(),link_offset.end());
122 std::reverse(solver_info_.limits.begin(),solver_info_.limits.end());
123 std::reverse(solver_info_.joint_names.begin(),solver_info_.joint_names.end());
124 std::reverse(solver_info_.link_names.begin(),solver_info_.link_names.end());
125 std::reverse(continuous_joint_.begin(),continuous_joint_.end());
129 ROS_FATAL(
"PR2ArmIK:: Chain from %s to %s does not have 7 joints",root_name.c_str(),tip_name.c_str());
133 torso_shoulder_offset_x_ = link_offset[0].position.x;
134 torso_shoulder_offset_y_ = link_offset[0].position.y;
135 torso_shoulder_offset_z_ = link_offset[0].position.z;
136 shoulder_upperarm_offset_ =
distance(link_offset[1]);
137 upperarm_elbow_offset_ =
distance(link_offset[3]);
138 elbow_wrist_offset_ =
distance(link_offset[5]);
139 shoulder_elbow_offset_ = shoulder_upperarm_offset_ + upperarm_elbow_offset_;
140 shoulder_wrist_offset_ = shoulder_upperarm_offset_+upperarm_elbow_offset_+elbow_wrist_offset_;
142 Eigen::Matrix4f home = Eigen::Matrix4f::Identity();
143 home(0,3) = shoulder_upperarm_offset_ + upperarm_elbow_offset_ + elbow_wrist_offset_;
144 home_inv_ = home.inverse();
147 solution_.resize( NUM_JOINTS_ARM7DOF);
151 void PR2ArmIK::addJointToChainInfo(urdf::JointConstSharedPtr joint, moveit_msgs::KinematicSolverInfo &info)
153 moveit_msgs::JointLimits limit;
154 info.joint_names.push_back(joint->name);
156 if(joint->type != urdf::Joint::CONTINUOUS)
160 limit.min_position = joint->safety->soft_lower_limit;
161 limit.max_position = joint->safety->soft_upper_limit;
162 limit.has_position_limits =
true;
167 limit.min_position = joint->limits->lower;
168 limit.max_position = joint->limits->upper;
169 limit.has_position_limits =
true;
172 limit.has_position_limits =
false;
176 limit.min_position = -
M_PI;
177 limit.max_position =
M_PI;
178 limit.has_position_limits =
false;
182 limit.max_velocity = joint->limits->velocity;
183 limit.has_velocity_limits = 1;
186 limit.has_velocity_limits = 0;
187 info.limits.push_back(limit);
190 void PR2ArmIK::getSolverInfo(moveit_msgs::KinematicSolverInfo &info)
196 void PR2ArmIK::computeIKShoulderPan(
const Eigen::Matrix4f &g_in,
const double &t1_in, std::vector<std::vector<double> > &solution)
const 200 std::vector<double> solution_ik(NUM_JOINTS_ARM7DOF,0.0);
201 Eigen::Matrix4f g = g_in;
202 Eigen::Matrix4f gf_local = home_inv_;
203 Eigen::Matrix4f grhs_local = home_inv_;
205 g(0,3) = g_in(0,3) - torso_shoulder_offset_x_;
206 g(1,3) = g_in(1,3) - torso_shoulder_offset_y_;
207 g(2,3) = g_in(2,3) - torso_shoulder_offset_z_;
210 if(!checkJointLimits(t1,0))
214 double cost1, cost2, cost3, cost4;
215 double sint1, sint2, sint3, sint4;
217 gf_local = g*home_inv_;
222 double t2(0), t3(0), t4(0), t5(0), t6(0), t7(0);
224 double at(0), bt(0), ct(0);
226 double theta2[2],theta3[2],theta4[2],theta5[2],theta6[4],theta7[2];
228 double sopx = shoulder_upperarm_offset_*cost1;
229 double sopy = shoulder_upperarm_offset_*sint1;
236 double dx = x - sopx;
237 double dy = y - sopy;
238 double dz = z - sopz;
240 double dd = dx*dx + dy*dy + dz*dz;
242 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_;
243 double denominator = 2*(shoulder_upperarm_offset_-shoulder_elbow_offset_)*(shoulder_elbow_offset_-shoulder_wrist_offset_);
245 double acosTerm = numerator/denominator;
247 if (acosTerm > 1.0 || acosTerm < -1.0)
250 double acos_angle =
acos(acosTerm);
252 theta4[0] = acos_angle;
253 theta4[1] = -acos_angle;
256 std::cout <<
"ComputeIK::theta3:" << numerator <<
"," << denominator <<
"," << std::endl << theta4[0] << std::endl;
259 for(
int jj =0; jj < 2; jj++)
266 std::cout <<
"t4 " << t4 << std::endl;
271 if(!checkJointLimits(t4,3))
274 at = x*cost1+y*sint1-shoulder_upperarm_offset_;
276 ct = -shoulder_upperarm_offset_ + shoulder_elbow_offset_ + (shoulder_wrist_offset_-shoulder_elbow_offset_)*
cos(t4);
281 for(
int ii=0; ii < 2; ii++)
284 if(!checkJointLimits(t2,1))
289 std::cout <<
"t2 " << t2 << std::endl;
294 at = sint1*(shoulder_elbow_offset_ - shoulder_wrist_offset_)*sint2*sint4;
295 bt = (-shoulder_elbow_offset_+shoulder_wrist_offset_)*cost1*sint4;
296 ct = y - (shoulder_upperarm_offset_+cost2*(-shoulder_upperarm_offset_+shoulder_elbow_offset_+(-shoulder_elbow_offset_+shoulder_wrist_offset_)*
cos(t4)))*sint1;
300 for(
int kk =0; kk < 2; kk++)
310 std::cout <<
"t3 " << t3 << std::endl;
312 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 )
315 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)
318 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;
320 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;
322 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;
324 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;
326 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;
328 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;
330 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;
332 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;
334 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;
337 double val1 =
sqrt(grhs_local(0,1)*grhs_local(0,1)+grhs_local(0,2)*grhs_local(0,2));
338 double val2 = grhs_local(0,0);
340 theta6[0] =
atan2(val1,val2);
341 theta6[1] =
atan2(-val1,val2);
346 for(
int mm = 0; mm < 2; mm++)
353 std::cout <<
"t6 " << t6 << std::endl;
355 if(fabs(
cos(t6) - grhs_local(0,0)) > IK_EPS)
358 if(fabs(
sin(t6)) < IK_EPS)
361 theta5[0] =
acos(grhs_local(1,1))/2.0;
362 theta7[0] = theta7[0];
363 theta7[1] =
M_PI+theta7[0];
364 theta5[1] = theta7[1];
368 theta7[0] =
atan2(grhs_local(0,1),grhs_local(0,2));
369 theta5[0] =
atan2(grhs_local(1,0),-grhs_local(2,0));
370 theta7[1] =
M_PI+theta7[0];
371 theta5[1] =
M_PI+theta5[0];
374 std::cout <<
"theta1: " << t1 << std::endl;
375 std::cout <<
"theta2: " << t2 << std::endl;
376 std::cout <<
"theta3: " << t3 << std::endl;
377 std::cout <<
"theta4: " << t4 << std::endl;
378 std::cout <<
"theta5: " << t5 << std::endl;
379 std::cout <<
"theta6: " << t6 << std::endl;
380 std::cout <<
"theta7: " << t7 << std::endl << std::endl << std::endl;
382 for(
int lll =0; lll < 2; lll++)
386 if(!checkJointLimits(t5,4))
388 if(!checkJointLimits(t7,6))
392 std::cout <<
"t5" << t5 << std::endl;
393 std::cout <<
"t7" << t7 << std::endl;
395 if(fabs(
sin(t6)*
sin(t7)-grhs_local(0,1)) > IK_EPS || fabs(
cos(t7)*
sin(t6)-grhs_local(0,2)) > IK_EPS)
405 solution.push_back(solution_ik);
408 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;
418 void PR2ArmIK::computeIKShoulderRoll(
const Eigen::Matrix4f &g_in,
const double &t3, std::vector<std::vector<double> > &solution)
const 420 std::vector<double> solution_ik(NUM_JOINTS_ARM7DOF,0.0);
431 Eigen::Matrix4f g = g_in;
432 Eigen::Matrix4f gf_local = home_inv_;
433 Eigen::Matrix4f grhs_local = home_inv_;
435 g(0,3) = g_in(0,3) - torso_shoulder_offset_x_;
436 g(1,3) = g_in(1,3) - torso_shoulder_offset_y_;
437 g(2,3) = g_in(2,3) - torso_shoulder_offset_z_;
439 if(!checkJointLimits(t3,2))
446 double cost1, cost2, cost3, cost4;
447 double sint1, sint2, sint3, sint4;
449 gf_local = g*home_inv_;
454 double t1(0), t2(0), t4(0), t5(0), t6(0), t7(0);
456 double at(0), bt(0), ct(0);
458 double theta1[2],theta2[2],theta4[4],theta5[2],theta6[4],theta7[2];
460 double c0 = -
sin(-t3)*elbow_wrist_offset_;
461 double c1 = -
cos(-t3)*elbow_wrist_offset_;
463 double d0 = 4*shoulder_upperarm_offset_*shoulder_upperarm_offset_*(upperarm_elbow_offset_*upperarm_elbow_offset_+c1*c1-z*z);
464 double d1 = 8*shoulder_upperarm_offset_*shoulder_upperarm_offset_*upperarm_elbow_offset_*elbow_wrist_offset_;
465 double d2 = 4*shoulder_upperarm_offset_*shoulder_upperarm_offset_*(elbow_wrist_offset_*elbow_wrist_offset_-c1*c1);
467 double b0 = x*x+y*y+z*z-shoulder_upperarm_offset_*shoulder_upperarm_offset_-upperarm_elbow_offset_*upperarm_elbow_offset_-c0*c0-c1*c1;
468 double b1 = -2*upperarm_elbow_offset_*elbow_wrist_offset_;
470 if(!
solveQuadratic(b1*b1-d2,2*b0*b1-d1,b0*b0-d0,&theta4[0],&theta4[1]))
473 printf(
"No solution to quadratic eqn\n");
477 theta4[0] =
acos(theta4[0]);
478 theta4[2] =
acos(theta4[1]);
479 theta4[1] = -theta4[0];
480 theta4[3] = -theta4[2];
482 for(
int jj = 0; jj < 4; jj++)
486 if(!checkJointLimits(t4,3))
493 std::cout <<
"t4 " << t4 << std::endl;
497 at =
cos(t3)*
sin(t4)*(shoulder_elbow_offset_-shoulder_wrist_offset_);
498 bt = (shoulder_upperarm_offset_-shoulder_elbow_offset_+(shoulder_elbow_offset_-shoulder_wrist_offset_)*
cos(t4));
504 for(
int ii=0; ii < 2; ii++)
508 std::cout <<
"t2 " << t2 << std::endl;
510 if(!checkJointLimits(t2,1))
521 ct = (shoulder_elbow_offset_-shoulder_wrist_offset_)*
sin(t3)*
sin(t4);
525 std::cout <<
"could not solve cosine equation for t1" << std::endl;
530 for(
int kk =0; kk < 2; kk++)
534 std::cout <<
"t1 " << t1 << std::endl;
536 if(!checkJointLimits(t1,0))
542 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 )
545 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));
549 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)
552 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));
556 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)
559 printf(
"y value not matched\n");
563 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;
565 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;
567 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;
569 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;
571 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;
573 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;
575 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;
577 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;
579 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;
589 double val1 =
sqrt(grhs_local(0,1)*grhs_local(0,1)+grhs_local(0,2)*grhs_local(0,2));
590 double val2 = grhs_local(0,0);
592 theta6[0] =
atan2(val1,val2);
593 theta6[1] =
atan2(-val1,val2);
595 for(
int mm = 0; mm < 2; mm++)
599 std::cout <<
"t6 " << t6 << std::endl;
601 if(!checkJointLimits(t6,5))
607 if(fabs(
cos(t6) - grhs_local(0,0)) > IK_EPS)
610 if(fabs(
sin(t6)) < IK_EPS)
613 theta5[0] =
acos(grhs_local(1,1))/2.0;
614 theta7[0] = theta5[0];
620 theta7[0] =
atan2(grhs_local(0,1)/
sin(t6),grhs_local(0,2)/
sin(t6));
621 theta5[0] =
atan2(grhs_local(1,0)/
sin(t6),-grhs_local(2,0)/
sin(t6));
625 for(
int lll =0; lll < 1; lll++)
630 if(!checkJointLimits(t5,4))
634 if(!checkJointLimits(t7,6))
641 std::cout <<
"t5 " << t5 << std::endl;
642 std::cout <<
"t7 " << t7 << std::endl;
648 std::cout <<
"theta1: " << t1 << std::endl;
649 std::cout <<
"theta2: " << t2 << std::endl;
650 std::cout <<
"theta3: " << t3 << std::endl;
651 std::cout <<
"theta4: " << t4 << std::endl;
652 std::cout <<
"theta5: " << t5 << std::endl;
653 std::cout <<
"theta6: " << t6 << std::endl;
654 std::cout <<
"theta7: " << t7 << std::endl << std::endl << std::endl;
660 solution_ik[2] = t3*angle_multipliers_[2];
665 solution.push_back(solution_ik);
667 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;
677 bool PR2ArmIK::checkJointLimits(
const std::vector<double> &joint_values)
const 679 for(
int i=0; i<NUM_JOINTS_ARM7DOF; i++)
689 bool PR2ArmIK::checkJointLimits(
const double &joint_value,
const int &joint_num)
const 692 if(continuous_joint_[joint_num])
694 else if (joint_num ==2)
695 jv = joint_value*angle_multipliers_[joint_num];
699 if(jv < min_angles_[joint_num] || jv > max_angles_[joint_num])
Namespace for the PR2ArmKinematics.
bool solveQuadratic(const double &a, const double &b, const double &c, double *x1, double *x2)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
def normalize_angle(angle)
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
double distance(const urdf::Pose &transform)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
bool solveCosineEqn(const double &a, const double &b, const double &c, double &soln1, double &soln2)