37 #include <angles/angles.h>
49 using namespace angles;
52 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_constaint_samplers.test.pr2_arm_ik");
58 bool PR2ArmIK::init(
const urdf::ModelInterface& robot_model,
const std::string& root_name,
const std::string& tip_name)
60 std::vector<urdf::Pose> link_offset;
62 urdf::LinkConstSharedPtr link = robot_model.getLink(tip_name);
63 while (link && num_joints < 7)
65 urdf::JointConstSharedPtr joint;
66 if (link->parent_joint)
67 joint = robot_model.getJoint(link->parent_joint->name);
70 if (link->parent_joint)
72 RCLCPP_ERROR(LOGGER,
"Could not find joint: %s", link->parent_joint->name.c_str());
76 RCLCPP_ERROR(LOGGER,
"Link %s has no parent joint", link->name.c_str());
82 link_offset.push_back(link->parent_joint->parent_to_joint_origin_transform);
83 angle_multipliers_.push_back(joint->axis.x * fabs(joint->axis.x) + joint->axis.y * fabs(joint->axis.y) +
84 joint->axis.z * fabs(joint->axis.z));
85 RCLCPP_DEBUG(LOGGER,
"Joint axis: %d, %f, %f, %f", 6 - num_joints, joint->axis.x, joint->axis.y, joint->axis.z);
86 if (joint->type != urdf::Joint::CONTINUOUS)
90 min_angles_.push_back(joint->safety->soft_lower_limit);
91 max_angles_.push_back(joint->safety->soft_upper_limit);
97 min_angles_.push_back(joint->limits->lower);
98 max_angles_.push_back(joint->limits->upper);
102 min_angles_.push_back(0.0);
103 max_angles_.push_back(0.0);
104 RCLCPP_WARN(LOGGER,
"No joint limits or joint '%s'", joint->name.c_str());
107 continuous_joint_.push_back(
false);
111 min_angles_.push_back(-M_PI);
112 max_angles_.push_back(M_PI);
113 continuous_joint_.push_back(
true);
115 addJointToChainInfo(link->parent_joint, solver_info_);
118 link = robot_model.getLink(link->getParent()->name);
121 solver_info_.link_names.push_back(tip_name);
125 std::reverse(angle_multipliers_.begin(), angle_multipliers_.end());
126 std::reverse(min_angles_.begin(), min_angles_.end());
127 std::reverse(max_angles_.begin(), max_angles_.end());
128 std::reverse(link_offset.begin(), link_offset.end());
129 std::reverse(solver_info_.limits.begin(), solver_info_.limits.end());
130 std::reverse(solver_info_.joint_names.begin(), solver_info_.joint_names.end());
131 std::reverse(solver_info_.link_names.begin(), solver_info_.link_names.end());
132 std::reverse(continuous_joint_.begin(), continuous_joint_.end());
136 RCLCPP_ERROR(LOGGER,
"PR2ArmIK:: Chain from %s to %s does not have 7 joints", root_name.c_str(), tip_name.c_str());
140 torso_shoulder_offset_x_ = link_offset[0].position.x;
141 torso_shoulder_offset_y_ = link_offset[0].position.y;
142 torso_shoulder_offset_z_ = link_offset[0].position.z;
143 shoulder_upperarm_offset_ =
distance(link_offset[1]);
144 upperarm_elbow_offset_ =
distance(link_offset[3]);
145 elbow_wrist_offset_ =
distance(link_offset[5]);
146 shoulder_elbow_offset_ = shoulder_upperarm_offset_ + upperarm_elbow_offset_;
147 shoulder_wrist_offset_ = shoulder_upperarm_offset_ + upperarm_elbow_offset_ + elbow_wrist_offset_;
149 Eigen::Isometry3f home = Eigen::Isometry3f::Identity();
150 home(0, 3) = shoulder_upperarm_offset_ + upperarm_elbow_offset_ + elbow_wrist_offset_;
151 home_inv_ = home.inverse();
154 solution_.resize(NUM_JOINTS_ARM7DOF);
158 void PR2ArmIK::addJointToChainInfo(
const urdf::JointConstSharedPtr& joint, moveit_msgs::msg::KinematicSolverInfo& info)
160 moveit_msgs::msg::JointLimits limit;
161 info.joint_names.push_back(joint->name);
163 if (joint->type != urdf::Joint::CONTINUOUS)
167 limit.min_position = joint->safety->soft_lower_limit;
168 limit.max_position = joint->safety->soft_upper_limit;
169 limit.has_position_limits =
true;
171 else if (joint->limits)
173 limit.min_position = joint->limits->lower;
174 limit.max_position = joint->limits->upper;
175 limit.has_position_limits =
true;
178 limit.has_position_limits =
false;
182 limit.min_position = -M_PI;
183 limit.max_position = M_PI;
184 limit.has_position_limits =
false;
188 limit.max_velocity = joint->limits->velocity;
189 limit.has_velocity_limits = 1;
192 limit.has_velocity_limits = 0;
193 info.limits.push_back(limit);
196 void PR2ArmIK::getSolverInfo(moveit_msgs::msg::KinematicSolverInfo& info)
201 void PR2ArmIK::computeIKShoulderPan(
const Eigen::Isometry3f& g_in,
const double& t1_in,
202 std::vector<std::vector<double> >& solution)
const
206 std::vector<double> solution_ik(NUM_JOINTS_ARM7DOF, 0.0);
207 Eigen::Isometry3f g = g_in;
208 Eigen::Isometry3f gf_local = home_inv_;
209 Eigen::Isometry3f grhs_local = home_inv_;
211 g(0, 3) = g_in(0, 3) - torso_shoulder_offset_x_;
212 g(1, 3) = g_in(1, 3) - torso_shoulder_offset_y_;
213 g(2, 3) = g_in(2, 3) - torso_shoulder_offset_z_;
215 double t1 = angles::normalize_angle(t1_in);
216 if (!checkJointLimits(t1, 0))
219 double cost1, cost2, cost3, cost4;
220 double sint1, sint2, sint3, sint4;
222 gf_local = g * home_inv_;
227 double t2(0), t3(0), t4(0), t5(0), t6(0), t7(0);
229 double at(0), bt(0), ct(0);
231 double theta2[2], theta3[2], theta4[2], theta5[2], theta6[4], theta7[2];
233 double sopx = shoulder_upperarm_offset_ * cost1;
234 double sopy = shoulder_upperarm_offset_ * sint1;
241 double dx =
x - sopx;
242 double dy =
y - sopy;
243 double dz =
z - sopz;
245 double dd = dx * dx + dy * dy + dz * dz;
248 dd - shoulder_upperarm_offset_ * shoulder_upperarm_offset_ +
249 2 * shoulder_upperarm_offset_ * shoulder_elbow_offset_ - 2 * shoulder_elbow_offset_ * shoulder_elbow_offset_ +
250 2 * shoulder_elbow_offset_ * shoulder_wrist_offset_ - shoulder_wrist_offset_ * shoulder_wrist_offset_;
252 2 * (shoulder_upperarm_offset_ - shoulder_elbow_offset_) * (shoulder_elbow_offset_ - shoulder_wrist_offset_);
254 double acos_term = numerator / denominator;
256 if (acos_term > 1.0 || acos_term < -1.0)
259 double acos_angle = acos(acos_term);
261 theta4[0] = acos_angle;
262 theta4[1] = -acos_angle;
265 std::cout <<
"ComputeIK::theta3:" << numerator <<
"," << denominator <<
",\n" << theta4[0] <<
'\n';
268 for (
double theta : theta4)
275 std::cout <<
"t4 " << t4 <<
'\n';
280 if (!checkJointLimits(t4, 3))
283 at =
x * cost1 +
y * sint1 - shoulder_upperarm_offset_;
285 ct = -shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
286 (shoulder_wrist_offset_ - shoulder_elbow_offset_) * cos(t4);
291 for (
double theta : theta2)
294 if (!checkJointLimits(t2, 1))
298 std::cout <<
"t2 " << t2 <<
'\n';
303 at = sint1 * (shoulder_elbow_offset_ - shoulder_wrist_offset_) * sint2 * sint4;
304 bt = (-shoulder_elbow_offset_ + shoulder_wrist_offset_) * cost1 * sint4;
305 ct =
y - (shoulder_upperarm_offset_ + cost2 * (-shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
306 (-shoulder_elbow_offset_ + shoulder_wrist_offset_) * cos(t4))) *
311 for (
double theta : theta3)
315 if (!checkJointLimits(angles::normalize_angle(t3), 2))
321 std::cout <<
"t3 " << t3 <<
'\n';
323 if (fabs((shoulder_upperarm_offset_ - shoulder_elbow_offset_ +
324 (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost4) *
326 (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost2 * cost3 * sint4 -
z) > IK_EPS)
329 if (fabs((shoulder_elbow_offset_ - shoulder_wrist_offset_) * sint1 * sint3 * sint4 +
330 cost1 * (shoulder_upperarm_offset_ +
331 cost2 * (-shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
332 (-shoulder_elbow_offset_ + shoulder_wrist_offset_) * cost4) +
333 (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost3 * sint2 * sint4) -
338 cost4 * (gf_local(0, 0) * cost1 * cost2 + gf_local(1, 0) * cost2 * sint1 - gf_local(2, 0) * sint2) -
339 (gf_local(2, 0) * cost2 * cost3 + cost3 * (gf_local(0, 0) * cost1 + gf_local(1, 0) * sint1) * sint2 +
340 (-(gf_local(1, 0) * cost1) + gf_local(0, 0) * sint1) * sint3) *
344 cost4 * (gf_local(0, 1) * cost1 * cost2 + gf_local(1, 1) * cost2 * sint1 - gf_local(2, 1) * sint2) -
345 (gf_local(2, 1) * cost2 * cost3 + cost3 * (gf_local(0, 1) * cost1 + gf_local(1, 1) * sint1) * sint2 +
346 (-(gf_local(1, 1) * cost1) + gf_local(0, 1) * sint1) * sint3) *
350 cost4 * (gf_local(0, 2) * cost1 * cost2 + gf_local(1, 2) * cost2 * sint1 - gf_local(2, 2) * sint2) -
351 (gf_local(2, 2) * cost2 * cost3 + cost3 * (gf_local(0, 2) * cost1 + gf_local(1, 2) * sint1) * sint2 +
352 (-(gf_local(1, 2) * cost1) + gf_local(0, 2) * sint1) * sint3) *
355 grhs_local(1, 0) = cost3 * (gf_local(1, 0) * cost1 - gf_local(0, 0) * sint1) + gf_local(2, 0) * cost2 * sint3 +
356 (gf_local(0, 0) * cost1 + gf_local(1, 0) * sint1) * sint2 * sint3;
358 grhs_local(1, 1) = cost3 * (gf_local(1, 1) * cost1 - gf_local(0, 1) * sint1) + gf_local(2, 1) * cost2 * sint3 +
359 (gf_local(0, 1) * cost1 + gf_local(1, 1) * sint1) * sint2 * sint3;
361 grhs_local(1, 2) = cost3 * (gf_local(1, 2) * cost1 - gf_local(0, 2) * sint1) + gf_local(2, 2) * cost2 * sint3 +
362 (gf_local(0, 2) * cost1 + gf_local(1, 2) * sint1) * sint2 * sint3;
366 (gf_local(2, 0) * cost2 * cost3 + cost3 * (gf_local(0, 0) * cost1 + gf_local(1, 0) * sint1) * sint2 +
367 (-(gf_local(1, 0) * cost1) + gf_local(0, 0) * sint1) * sint3) +
368 (gf_local(0, 0) * cost1 * cost2 + gf_local(1, 0) * cost2 * sint1 - gf_local(2, 0) * sint2) * sint4;
372 (gf_local(2, 1) * cost2 * cost3 + cost3 * (gf_local(0, 1) * cost1 + gf_local(1, 1) * sint1) * sint2 +
373 (-(gf_local(1, 1) * cost1) + gf_local(0, 1) * sint1) * sint3) +
374 (gf_local(0, 1) * cost1 * cost2 + gf_local(1, 1) * cost2 * sint1 - gf_local(2, 1) * sint2) * sint4;
378 (gf_local(2, 2) * cost2 * cost3 + cost3 * (gf_local(0, 2) * cost1 + gf_local(1, 2) * sint1) * sint2 +
379 (-(gf_local(1, 2) * cost1) + gf_local(0, 2) * sint1) * sint3) +
380 (gf_local(0, 2) * cost1 * cost2 + gf_local(1, 2) * cost2 * sint1 - gf_local(2, 2) * sint2) * sint4;
382 double val1 = sqrt(grhs_local(0, 1) * grhs_local(0, 1) + grhs_local(0, 2) * grhs_local(0, 2));
383 double val2 = grhs_local(0, 0);
385 theta6[0] = atan2(val1, val2);
386 theta6[1] = atan2(-val1, val2);
391 for (
int mm = 0; mm < 2; ++mm)
394 if (!checkJointLimits(angles::normalize_angle(t6), 5))
398 std::cout <<
"t6 " << t6 <<
'\n';
400 if (fabs(cos(t6) - grhs_local(0, 0)) > IK_EPS)
403 if (fabs(sin(t6)) < IK_EPS)
406 theta5[0] = acos(grhs_local(1, 1)) / 2.0;
407 theta7[0] = theta7[0];
408 theta7[1] = M_PI + theta7[0];
409 theta5[1] = theta7[1];
413 theta7[0] = atan2(grhs_local(0, 1), grhs_local(0, 2));
414 theta5[0] = atan2(grhs_local(1, 0), -grhs_local(2, 0));
415 theta7[1] = M_PI + theta7[0];
416 theta5[1] = M_PI + theta5[0];
419 std::cout <<
"theta1: " << t1 <<
'\n';
420 std::cout <<
"theta2: " << t2 <<
'\n';
421 std::cout <<
"theta3: " << t3 <<
'\n';
422 std::cout <<
"theta4: " << t4 <<
'\n';
423 std::cout <<
"theta5: " << t5 <<
'\n';
424 std::cout <<
"theta6: " << t6 <<
'\n';
425 std::cout <<
"theta7: " << t7 <<
'\n' <<
'\n' <<
'\n';
427 for (
int lll = 0; lll < 2; ++lll)
431 if (!checkJointLimits(t5, 4))
433 if (!checkJointLimits(t7, 6))
437 std::cout <<
"t5" << t5 <<
'\n';
438 std::cout <<
"t7" << t7 <<
'\n';
440 if (fabs(sin(t6) * sin(t7) - grhs_local(0, 1)) > IK_EPS ||
441 fabs(cos(t7) * sin(t6) - grhs_local(0, 2)) > IK_EPS)
444 solution_ik[0] = normalize_angle(t1) * angle_multipliers_[0];
445 solution_ik[1] = normalize_angle(t2) * angle_multipliers_[1];
446 solution_ik[2] = normalize_angle(t3) * angle_multipliers_[2];
447 solution_ik[3] = normalize_angle(t4) * angle_multipliers_[3];
448 solution_ik[4] = normalize_angle(t5) * angle_multipliers_[4];
449 solution_ik[5] = normalize_angle(t6) * angle_multipliers_[5];
450 solution_ik[6] = normalize_angle(t7) * angle_multipliers_[6];
451 solution.push_back(solution_ik);
454 std::cout <<
"SOLN " << solution_ik[0] <<
" " << solution_ik[1] <<
" " << solution_ik[2] <<
" "
455 << solution_ik[3] <<
" " << solution_ik[4] <<
" " << solution_ik[5] <<
" " << solution_ik[6]
466 void PR2ArmIK::computeIKShoulderRoll(
const Eigen::Isometry3f& g_in,
const double& t3,
467 std::vector<std::vector<double> >& solution)
const
469 std::vector<double> solution_ik(NUM_JOINTS_ARM7DOF, 0.0);
480 Eigen::Isometry3f g = g_in;
481 Eigen::Isometry3f gf_local = home_inv_;
482 Eigen::Isometry3f grhs_local = home_inv_;
484 g(0, 3) = g_in(0, 3) - torso_shoulder_offset_x_;
485 g(1, 3) = g_in(1, 3) - torso_shoulder_offset_y_;
486 g(2, 3) = g_in(2, 3) - torso_shoulder_offset_z_;
488 if (!checkJointLimits(t3, 2))
495 double cost1, cost2, cost3, cost4;
496 double sint1, sint2, sint3, sint4;
498 gf_local = g * home_inv_;
503 double t1(0), t2(0), t4(0), t5(0), t6(0), t7(0);
505 double at(0), bt(0), ct(0);
507 double theta1[2], theta2[2], theta4[4], theta5[2], theta6[4], theta7[2];
509 double c0 = -sin(-t3) * elbow_wrist_offset_;
510 double c1 = -cos(-t3) * elbow_wrist_offset_;
512 double d0 = 4 * shoulder_upperarm_offset_ * shoulder_upperarm_offset_ *
513 (upperarm_elbow_offset_ * upperarm_elbow_offset_ + c1 * c1 -
z *
z);
514 double d1 = 8 * shoulder_upperarm_offset_ * shoulder_upperarm_offset_ * upperarm_elbow_offset_ * elbow_wrist_offset_;
516 4 * shoulder_upperarm_offset_ * shoulder_upperarm_offset_ * (elbow_wrist_offset_ * elbow_wrist_offset_ - c1 * c1);
518 double b0 =
x *
x +
y *
y +
z *
z - shoulder_upperarm_offset_ * shoulder_upperarm_offset_ -
519 upperarm_elbow_offset_ * upperarm_elbow_offset_ - c0 * c0 - c1 * c1;
520 double b1 = -2 * upperarm_elbow_offset_ * elbow_wrist_offset_;
522 if (!
solveQuadratic(b1 * b1 - d2, 2 * b0 * b1 - d1, b0 * b0 - d0, &theta4[0], &theta4[1]))
525 printf(
"No solution to quadratic eqn\n");
529 theta4[0] = acos(theta4[0]);
530 theta4[2] = acos(theta4[1]);
531 theta4[1] = -theta4[0];
532 theta4[3] = -theta4[2];
534 for (
double theta : theta4)
538 if (!checkJointLimits(t4, 3))
545 std::cout <<
"t4 " << t4 <<
'\n';
549 at = cos(t3) * sin(t4) * (shoulder_elbow_offset_ - shoulder_wrist_offset_);
550 bt = (shoulder_upperarm_offset_ - shoulder_elbow_offset_ +
551 (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cos(t4));
557 for (
double theta : theta2)
561 std::cout <<
"t2 " << t2 <<
'\n';
563 if (!checkJointLimits(t2, 1))
573 ct = (shoulder_elbow_offset_ - shoulder_wrist_offset_) * sin(t3) * sin(t4);
577 std::cout <<
"could not solve cosine equation for t1" <<
'\n';
582 for (
double theta : theta1)
586 std::cout <<
"t1 " << t1 <<
'\n';
588 if (!checkJointLimits(t1, 0))
594 if (fabs((shoulder_upperarm_offset_ - shoulder_elbow_offset_ +
595 (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost4) *
597 (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost2 * cost3 * sint4 -
z) > IK_EPS)
600 printf(
"z value not matched %f\n",
601 fabs((shoulder_upperarm_offset_ - shoulder_elbow_offset_ +
602 (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost4) *
604 (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost2 * cost3 * sint4 -
z));
608 if (fabs((shoulder_elbow_offset_ - shoulder_wrist_offset_) * sint1 * sint3 * sint4 +
609 cost1 * (shoulder_upperarm_offset_ +
610 cost2 * (-shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
611 (-shoulder_elbow_offset_ + shoulder_wrist_offset_) * cost4) +
612 (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost3 * sint2 * sint4) -
616 printf(
"x value not matched by %f\n",
617 fabs((shoulder_elbow_offset_ - shoulder_wrist_offset_) * sint1 * sint3 * sint4 +
618 cost1 * (shoulder_upperarm_offset_ +
619 cost2 * (-shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
620 (-shoulder_elbow_offset_ + shoulder_wrist_offset_) * cost4) +
621 (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost3 * sint2 * sint4) -
626 if (fabs(-(shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost1 * sint3 * sint4 +
627 sint1 * (shoulder_upperarm_offset_ +
628 cost2 * (-shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
629 (-shoulder_elbow_offset_ + shoulder_wrist_offset_) * cost4) +
630 (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost3 * sint2 * sint4) -
634 printf(
"y value not matched\n");
639 cost4 * (gf_local(0, 0) * cost1 * cost2 + gf_local(1, 0) * cost2 * sint1 - gf_local(2, 0) * sint2) -
640 (gf_local(2, 0) * cost2 * cost3 + cost3 * (gf_local(0, 0) * cost1 + gf_local(1, 0) * sint1) * sint2 +
641 (-(gf_local(1, 0) * cost1) + gf_local(0, 0) * sint1) * sint3) *
645 cost4 * (gf_local(0, 1) * cost1 * cost2 + gf_local(1, 1) * cost2 * sint1 - gf_local(2, 1) * sint2) -
646 (gf_local(2, 1) * cost2 * cost3 + cost3 * (gf_local(0, 1) * cost1 + gf_local(1, 1) * sint1) * sint2 +
647 (-(gf_local(1, 1) * cost1) + gf_local(0, 1) * sint1) * sint3) *
651 cost4 * (gf_local(0, 2) * cost1 * cost2 + gf_local(1, 2) * cost2 * sint1 - gf_local(2, 2) * sint2) -
652 (gf_local(2, 2) * cost2 * cost3 + cost3 * (gf_local(0, 2) * cost1 + gf_local(1, 2) * sint1) * sint2 +
653 (-(gf_local(1, 2) * cost1) + gf_local(0, 2) * sint1) * sint3) *
656 grhs_local(1, 0) = cost3 * (gf_local(1, 0) * cost1 - gf_local(0, 0) * sint1) + gf_local(2, 0) * cost2 * sint3 +
657 (gf_local(0, 0) * cost1 + gf_local(1, 0) * sint1) * sint2 * sint3;
659 grhs_local(1, 1) = cost3 * (gf_local(1, 1) * cost1 - gf_local(0, 1) * sint1) + gf_local(2, 1) * cost2 * sint3 +
660 (gf_local(0, 1) * cost1 + gf_local(1, 1) * sint1) * sint2 * sint3;
662 grhs_local(1, 2) = cost3 * (gf_local(1, 2) * cost1 - gf_local(0, 2) * sint1) + gf_local(2, 2) * cost2 * sint3 +
663 (gf_local(0, 2) * cost1 + gf_local(1, 2) * sint1) * sint2 * sint3;
667 (gf_local(2, 0) * cost2 * cost3 + cost3 * (gf_local(0, 0) * cost1 + gf_local(1, 0) * sint1) * sint2 +
668 (-(gf_local(1, 0) * cost1) + gf_local(0, 0) * sint1) * sint3) +
669 (gf_local(0, 0) * cost1 * cost2 + gf_local(1, 0) * cost2 * sint1 - gf_local(2, 0) * sint2) * sint4;
673 (gf_local(2, 1) * cost2 * cost3 + cost3 * (gf_local(0, 1) * cost1 + gf_local(1, 1) * sint1) * sint2 +
674 (-(gf_local(1, 1) * cost1) + gf_local(0, 1) * sint1) * sint3) +
675 (gf_local(0, 1) * cost1 * cost2 + gf_local(1, 1) * cost2 * sint1 - gf_local(2, 1) * sint2) * sint4;
679 (gf_local(2, 2) * cost2 * cost3 + cost3 * (gf_local(0, 2) * cost1 + gf_local(1, 2) * sint1) * sint2 +
680 (-(gf_local(1, 2) * cost1) + gf_local(0, 2) * sint1) * sint3) +
681 (gf_local(0, 2) * cost1 * cost2 + gf_local(1, 2) * cost2 * sint1 - gf_local(2, 2) * sint2) * sint4;
683 double val1 = sqrt(grhs_local(0, 1) * grhs_local(0, 1) + grhs_local(0, 2) * grhs_local(0, 2));
684 double val2 = grhs_local(0, 0);
686 theta6[0] = atan2(val1, val2);
687 theta6[1] = atan2(-val1, val2);
689 for (
int mm = 0; mm < 2; ++mm)
693 std::cout <<
"t6 " << t6 <<
'\n';
695 if (!checkJointLimits(t6, 5))
700 if (fabs(cos(t6) - grhs_local(0, 0)) > IK_EPS)
703 if (fabs(sin(t6)) < IK_EPS)
706 theta5[0] = acos(grhs_local(1, 1)) / 2.0;
707 theta7[0] = theta5[0];
713 theta7[0] = atan2(grhs_local(0, 1) / sin(t6), grhs_local(0, 2) / sin(t6));
714 theta5[0] = atan2(grhs_local(1, 0) / sin(t6), -grhs_local(2, 0) / sin(t6));
718 for (
int lll = 0; lll < 1; ++lll)
723 if (!checkJointLimits(t5, 4))
727 if (!checkJointLimits(t7, 6))
733 std::cout <<
"t5 " << t5 <<
'\n';
734 std::cout <<
"t7 " << t7 <<
'\n';
740 std::cout <<
"theta1: " << t1 <<
'\n';
741 std::cout <<
"theta2: " << t2 <<
'\n';
742 std::cout <<
"theta3: " << t3 <<
'\n';
743 std::cout <<
"theta4: " << t4 <<
'\n';
744 std::cout <<
"theta5: " << t5 <<
'\n';
745 std::cout <<
"theta6: " << t6 <<
'\n';
746 std::cout <<
"theta7: " << t7 <<
'\n' <<
'\n' <<
'\n';
749 solution_ik[0] = normalize_angle(t1 * angle_multipliers_[0]);
750 solution_ik[1] = normalize_angle(t2 * angle_multipliers_[1]);
751 solution_ik[2] = t3 * angle_multipliers_[2];
752 solution_ik[3] = normalize_angle(t4 * angle_multipliers_[3]);
753 solution_ik[4] = normalize_angle(t5 * angle_multipliers_[4]);
754 solution_ik[5] = normalize_angle(t6 * angle_multipliers_[5]);
755 solution_ik[6] = normalize_angle(t7 * angle_multipliers_[6]);
756 solution.push_back(solution_ik);
758 std::cout <<
"SOLN " << solution_ik[0] <<
" " << solution_ik[1] <<
" " << solution_ik[2] <<
" "
759 << solution_ik[3] <<
" " << solution_ik[4] <<
" " << solution_ik[5] <<
" " << solution_ik[6]
770 bool PR2ArmIK::checkJointLimits(
const std::vector<double>& joint_values)
const
772 for (
int i = 0; i < NUM_JOINTS_ARM7DOF; ++i)
774 if (!checkJointLimits(angles::normalize_angle(joint_values[i] * angle_multipliers_[i]), i))
782 bool PR2ArmIK::checkJointLimits(
const double& joint_value,
const int& joint_num)
const
785 if (continuous_joint_[joint_num])
786 jv = angles::normalize_angle(joint_value * angle_multipliers_[joint_num]);
787 else if (joint_num == 2)
788 jv = joint_value * angle_multipliers_[joint_num];
790 jv = angles::normalize_angle(joint_value * angle_multipliers_[joint_num]);
792 return !(jv < min_angles_[joint_num] || jv > max_angles_[joint_num]);
double distance(const urdf::Pose &transform)
bool solveCosineEqn(const double &a, const double &b, const double &c, double &soln1, double &soln2)
bool solveQuadratic(const double &a, const double &b, const double &c, double *x1, double *x2)