moveit2
The MoveIt Motion Planning Framework for ROS 2.
pr2_arm_ik.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Sachin Chitta, E. Gil Jones */
36 
37 #include <angles/angles.h>
38 #include "pr2_arm_ik.h"
39 
40 /**** List of angles (for reference) *******
41  th1 = shoulder/turret pan
42  th2 = shoulder/turret lift/pitch
43  th3 = shoulder/turret roll
44  th4 = elbow pitch
45  th5 = elbow roll
46  th6 = wrist pitch
47  th7 = wrist roll
48 *****/
49 using namespace angles;
51 {
52 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_constaint_samplers.test.pr2_arm_ik");
53 
54 PR2ArmIK::PR2ArmIK()
55 {
56 }
57 
58 bool PR2ArmIK::init(const urdf::ModelInterface& robot_model, const std::string& root_name, const std::string& tip_name)
59 {
60  std::vector<urdf::Pose> link_offset;
61  int num_joints = 0;
62  urdf::LinkConstSharedPtr link = robot_model.getLink(tip_name);
63  while (link && num_joints < 7)
64  {
65  urdf::JointConstSharedPtr joint;
66  if (link->parent_joint)
67  joint = robot_model.getJoint(link->parent_joint->name);
68  if (!joint)
69  {
70  if (link->parent_joint)
71  {
72  RCLCPP_ERROR(LOGGER, "Could not find joint: %s", link->parent_joint->name.c_str());
73  }
74  else
75  {
76  RCLCPP_ERROR(LOGGER, "Link %s has no parent joint", link->name.c_str());
77  }
78  return false;
79  }
80  if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
81  {
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)
87  {
88  if (joint->safety)
89  {
90  min_angles_.push_back(joint->safety->soft_lower_limit);
91  max_angles_.push_back(joint->safety->soft_upper_limit);
92  }
93  else
94  {
95  if (joint->limits)
96  {
97  min_angles_.push_back(joint->limits->lower);
98  max_angles_.push_back(joint->limits->upper);
99  }
100  else
101  {
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());
105  }
106  }
107  continuous_joint_.push_back(false);
108  }
109  else
110  {
111  min_angles_.push_back(-M_PI);
112  max_angles_.push_back(M_PI);
113  continuous_joint_.push_back(true);
114  }
115  addJointToChainInfo(link->parent_joint, solver_info_);
116  num_joints++;
117  }
118  link = robot_model.getLink(link->getParent()->name);
119  }
120 
121  solver_info_.link_names.push_back(tip_name);
122 
123  // solver_info_.link_names.push_back(tip_name);
124  // We expect order from root to tip, so reverse the order
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());
133 
134  if (num_joints != 7)
135  {
136  RCLCPP_ERROR(LOGGER, "PR2ArmIK:: Chain from %s to %s does not have 7 joints", root_name.c_str(), tip_name.c_str());
137  return false;
138  }
139 
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_;
148 
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();
152  grhs_ = home;
153  gf_ = home_inv_;
154  solution_.resize(NUM_JOINTS_ARM7DOF);
155  return true;
156 }
157 
158 void PR2ArmIK::addJointToChainInfo(const urdf::JointConstSharedPtr& joint, moveit_msgs::msg::KinematicSolverInfo& info)
159 {
160  moveit_msgs::msg::JointLimits limit;
161  info.joint_names.push_back(joint->name); // Joints are coming in reverse order
162 
163  if (joint->type != urdf::Joint::CONTINUOUS)
164  {
165  if (joint->safety)
166  {
167  limit.min_position = joint->safety->soft_lower_limit;
168  limit.max_position = joint->safety->soft_upper_limit;
169  limit.has_position_limits = true;
170  }
171  else if (joint->limits)
172  {
173  limit.min_position = joint->limits->lower;
174  limit.max_position = joint->limits->upper;
175  limit.has_position_limits = true;
176  }
177  else
178  limit.has_position_limits = false;
179  }
180  else
181  {
182  limit.min_position = -M_PI;
183  limit.max_position = M_PI;
184  limit.has_position_limits = false;
185  }
186  if (joint->limits)
187  {
188  limit.max_velocity = joint->limits->velocity;
189  limit.has_velocity_limits = 1;
190  }
191  else
192  limit.has_velocity_limits = 0;
193  info.limits.push_back(limit);
194 }
195 
196 void PR2ArmIK::getSolverInfo(moveit_msgs::msg::KinematicSolverInfo& info)
197 {
198  info = solver_info_;
199 }
200 
201 void PR2ArmIK::computeIKShoulderPan(const Eigen::Isometry3f& g_in, const double& t1_in,
202  std::vector<std::vector<double> >& solution) const
203 {
204  // t1 = shoulder/turret pan is specified
205  // solution_ik_.resize(0);
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_;
210  // First bring everything into the arm frame
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_;
214 
215  double t1 = angles::normalize_angle(t1_in);
216  if (!checkJointLimits(t1, 0))
217  return;
218 
219  double cost1, cost2, cost3, cost4;
220  double sint1, sint2, sint3, sint4;
221 
222  gf_local = g * home_inv_;
223 
224  cost1 = cos(t1);
225  sint1 = sin(t1);
226 
227  double t2(0), t3(0), t4(0), t5(0), t6(0), t7(0);
228 
229  double at(0), bt(0), ct(0);
230 
231  double theta2[2], theta3[2], theta4[2], theta5[2], theta6[4], theta7[2];
232 
233  double sopx = shoulder_upperarm_offset_ * cost1;
234  double sopy = shoulder_upperarm_offset_ * sint1;
235  double sopz = 0;
236 
237  double x = g(0, 3);
238  double y = g(1, 3);
239  double z = g(2, 3);
240 
241  double dx = x - sopx;
242  double dy = y - sopy;
243  double dz = z - sopz;
244 
245  double dd = dx * dx + dy * dy + dz * dz;
246 
247  double numerator =
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_;
251  double denominator =
252  2 * (shoulder_upperarm_offset_ - shoulder_elbow_offset_) * (shoulder_elbow_offset_ - shoulder_wrist_offset_);
253 
254  double acos_term = numerator / denominator;
255 
256  if (acos_term > 1.0 || acos_term < -1.0)
257  return;
258 
259  double acos_angle = acos(acos_term);
260 
261  theta4[0] = acos_angle;
262  theta4[1] = -acos_angle;
263 
264 #ifdef DEBUG
265  std::cout << "ComputeIK::theta3:" << numerator << "," << denominator << ",\n" << theta4[0] << '\n';
266 #endif
267 
268  for (double theta : theta4)
269  {
270  t4 = theta;
271  cost4 = cos(t4);
272  sint4 = sin(t4);
273 
274 #ifdef DEBUG
275  std::cout << "t4 " << t4 << '\n';
276 #endif
277  if (std::isnan(t4))
278  continue;
279 
280  if (!checkJointLimits(t4, 3))
281  continue;
282 
283  at = x * cost1 + y * sint1 - shoulder_upperarm_offset_;
284  bt = -z;
285  ct = -shoulder_upperarm_offset_ + shoulder_elbow_offset_ +
286  (shoulder_wrist_offset_ - shoulder_elbow_offset_) * cos(t4);
287 
288  if (!solveCosineEqn(at, bt, ct, theta2[0], theta2[1]))
289  continue;
290 
291  for (double theta : theta2)
292  {
293  t2 = theta;
294  if (!checkJointLimits(t2, 1))
295  continue;
296 
297 #ifdef DEBUG
298  std::cout << "t2 " << t2 << '\n';
299 #endif
300  sint2 = sin(t2);
301  cost2 = cos(t2);
302 
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))) *
307  sint1;
308  if (!solveCosineEqn(at, bt, ct, theta3[0], theta3[1]))
309  continue;
310 
311  for (double theta : theta3)
312  {
313  t3 = theta;
314 
315  if (!checkJointLimits(angles::normalize_angle(t3), 2))
316  continue;
317 
318  sint3 = sin(t3);
319  cost3 = cos(t3);
320 #ifdef DEBUG
321  std::cout << "t3 " << t3 << '\n';
322 #endif
323  if (fabs((shoulder_upperarm_offset_ - shoulder_elbow_offset_ +
324  (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost4) *
325  sint2 +
326  (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost2 * cost3 * sint4 - z) > IK_EPS)
327  continue;
328 
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) -
334  x) > IK_EPS)
335  continue;
336 
337  grhs_local(0, 0) =
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) *
341  sint4;
342 
343  grhs_local(0, 1) =
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) *
347  sint4;
348 
349  grhs_local(0, 2) =
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) *
353  sint4;
354 
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;
357 
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;
360 
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;
363 
364  grhs_local(2, 0) =
365  cost4 *
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;
369 
370  grhs_local(2, 1) =
371  cost4 *
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;
375 
376  grhs_local(2, 2) =
377  cost4 *
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;
381 
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);
384 
385  theta6[0] = atan2(val1, val2);
386  theta6[1] = atan2(-val1, val2);
387 
388  // theta6[3] = M_PI + theta6[0];
389  // theta6[4] = M_PI + theta6[1];
390 
391  for (int mm = 0; mm < 2; ++mm)
392  {
393  t6 = theta6[mm];
394  if (!checkJointLimits(angles::normalize_angle(t6), 5))
395  continue;
396 
397 #ifdef DEBUG
398  std::cout << "t6 " << t6 << '\n';
399 #endif
400  if (fabs(cos(t6) - grhs_local(0, 0)) > IK_EPS)
401  continue;
402 
403  if (fabs(sin(t6)) < IK_EPS)
404  {
405  // std::cout << "Singularity" << '\n';
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];
410  }
411  else
412  {
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];
417  }
418 #ifdef DEBUG
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';
426 #endif
427  for (int lll = 0; lll < 2; ++lll)
428  {
429  t5 = theta5[lll];
430  t7 = theta7[lll];
431  if (!checkJointLimits(t5, 4))
432  continue;
433  if (!checkJointLimits(t7, 6))
434  continue;
435 
436 #ifdef DEBUG
437  std::cout << "t5" << t5 << '\n';
438  std::cout << "t7" << t7 << '\n';
439 #endif
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)
442  continue;
443 
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);
452 
453 #ifdef DEBUG
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]
456  << '\n'
457  << '\n';
458 #endif
459  }
460  }
461  }
462  }
463  }
464 }
465 
466 void PR2ArmIK::computeIKShoulderRoll(const Eigen::Isometry3f& g_in, const double& t3,
467  std::vector<std::vector<double> >& solution) const
468 {
469  std::vector<double> solution_ik(NUM_JOINTS_ARM7DOF, 0.0);
470  // ROS_INFO(" ");
471  // solution_ik_.clear();
472  // ROS_INFO("Solution IK size: %d",solution_ik_.size());
473  // for(unsigned int i=0; i < solution_ik_.size(); ++i)
474  // {
475  // solution_ik_[i].clear();
476  // }
477  // if(!solution_ik_.empty())
478  // solution_ik_.resize(0);
479  // t3 = shoulder/turret roll is specified
480  Eigen::Isometry3f g = g_in;
481  Eigen::Isometry3f gf_local = home_inv_;
482  Eigen::Isometry3f grhs_local = home_inv_;
483  // First bring everything into the arm frame
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_;
487 
488  if (!checkJointLimits(t3, 2))
489  {
490  return;
491  }
492  double x = g(0, 3);
493  double y = g(1, 3);
494  double z = g(2, 3);
495  double cost1, cost2, cost3, cost4;
496  double sint1, sint2, sint3, sint4;
497 
498  gf_local = g * home_inv_;
499 
500  cost3 = cos(t3);
501  sint3 = sin(t3);
502 
503  double t1(0), t2(0), t4(0), t5(0), t6(0), t7(0);
504 
505  double at(0), bt(0), ct(0);
506 
507  double theta1[2], theta2[2], theta4[4], theta5[2], theta6[4], theta7[2];
508 
509  double c0 = -sin(-t3) * elbow_wrist_offset_;
510  double c1 = -cos(-t3) * elbow_wrist_offset_;
511 
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_;
515  double d2 =
516  4 * shoulder_upperarm_offset_ * shoulder_upperarm_offset_ * (elbow_wrist_offset_ * elbow_wrist_offset_ - c1 * c1);
517 
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_;
521 
522  if (!solveQuadratic(b1 * b1 - d2, 2 * b0 * b1 - d1, b0 * b0 - d0, &theta4[0], &theta4[1]))
523  {
524 #ifdef DEBUG
525  printf("No solution to quadratic eqn\n");
526 #endif
527  return;
528  }
529  theta4[0] = acos(theta4[0]);
530  theta4[2] = acos(theta4[1]);
531  theta4[1] = -theta4[0];
532  theta4[3] = -theta4[2];
533 
534  for (double theta : theta4)
535  {
536  t4 = theta;
537 
538  if (!checkJointLimits(t4, 3))
539  {
540  continue;
541  }
542  cost4 = cos(t4);
543  sint4 = sin(t4);
544 #ifdef DEBUG
545  std::cout << "t4 " << t4 << '\n';
546 #endif
547  if (std::isnan(t4))
548  continue;
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));
552  ct = z;
553 
554  if (!solveCosineEqn(at, bt, ct, theta2[0], theta2[1]))
555  continue;
556 
557  for (double theta : theta2)
558  {
559  t2 = theta;
560 #ifdef DEBUG
561  std::cout << "t2 " << t2 << '\n';
562 #endif
563  if (!checkJointLimits(t2, 1))
564  {
565  continue;
566  }
567 
568  sint2 = sin(t2);
569  cost2 = cos(t2);
570 
571  at = -y;
572  bt = x;
573  ct = (shoulder_elbow_offset_ - shoulder_wrist_offset_) * sin(t3) * sin(t4);
574  if (!solveCosineEqn(at, bt, ct, theta1[0], theta1[1]))
575  {
576 #ifdef DEBUG
577  std::cout << "could not solve cosine equation for t1" << '\n';
578 #endif
579  continue;
580  }
581 
582  for (double theta : theta1)
583  {
584  t1 = theta;
585 #ifdef DEBUG
586  std::cout << "t1 " << t1 << '\n';
587 #endif
588  if (!checkJointLimits(t1, 0))
589  {
590  continue;
591  }
592  sint1 = sin(t1);
593  cost1 = cos(t1);
594  if (fabs((shoulder_upperarm_offset_ - shoulder_elbow_offset_ +
595  (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost4) *
596  sint2 +
597  (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost2 * cost3 * sint4 - z) > IK_EPS)
598  {
599 #ifdef DEBUG
600  printf("z value not matched %f\n",
601  fabs((shoulder_upperarm_offset_ - shoulder_elbow_offset_ +
602  (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost4) *
603  sint2 +
604  (shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost2 * cost3 * sint4 - z));
605 #endif
606  continue;
607  }
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) -
613  x) > IK_EPS)
614  {
615 #ifdef DEBUG
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) -
622  x));
623 #endif
624  continue;
625  }
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) -
631  y) > IK_EPS)
632  {
633 #ifdef DEBUG
634  printf("y value not matched\n");
635 #endif
636  continue;
637  }
638  grhs_local(0, 0) =
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) *
642  sint4;
643 
644  grhs_local(0, 1) =
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) *
648  sint4;
649 
650  grhs_local(0, 2) =
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) *
654  sint4;
655 
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;
658 
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;
661 
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;
664 
665  grhs_local(2, 0) =
666  cost4 *
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;
670 
671  grhs_local(2, 1) =
672  cost4 *
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;
676 
677  grhs_local(2, 2) =
678  cost4 *
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;
682 
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);
685 
686  theta6[0] = atan2(val1, val2);
687  theta6[1] = atan2(-val1, val2);
688 
689  for (int mm = 0; mm < 2; ++mm)
690  {
691  t6 = theta6[mm];
692 #ifdef DEBUG
693  std::cout << "t6 " << t6 << '\n';
694 #endif
695  if (!checkJointLimits(t6, 5))
696  {
697  continue;
698  }
699 
700  if (fabs(cos(t6) - grhs_local(0, 0)) > IK_EPS)
701  continue;
702 
703  if (fabs(sin(t6)) < IK_EPS)
704  {
705  // std::cout << "Singularity" << '\n';
706  theta5[0] = acos(grhs_local(1, 1)) / 2.0;
707  theta7[0] = theta5[0];
708  // theta7[1] = M_PI+theta7[0];
709  // theta5[1] = theta7[1];
710  }
711  else
712  {
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));
715  // theta7[1] = M_PI+theta7[0];
716  // theta5[1] = M_PI+theta5[0];
717  }
718  for (int lll = 0; lll < 1; ++lll)
719  {
720  t5 = theta5[lll];
721  t7 = theta7[lll];
722 
723  if (!checkJointLimits(t5, 4))
724  {
725  continue;
726  }
727  if (!checkJointLimits(t7, 6))
728  {
729  continue;
730  }
731 
732 #ifdef DEBUG
733  std::cout << "t5 " << t5 << '\n';
734  std::cout << "t7 " << t7 << '\n';
735 #endif
736  // if(fabs(sin(t6)*sin(t7)-grhs_local(0,1)) > IK_EPS || fabs(cos(t7)*sin(t6)-grhs_local(0,2)) > IK_EPS)
737  // continue;
738 
739 #ifdef DEBUG
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';
747 #endif
748 
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);
757 #ifdef DEBUG
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]
760  << '\n'
761  << '\n';
762 #endif
763  }
764  }
765  }
766  }
767  }
768 }
769 
770 bool PR2ArmIK::checkJointLimits(const std::vector<double>& joint_values) const
771 {
772  for (int i = 0; i < NUM_JOINTS_ARM7DOF; ++i)
773  {
774  if (!checkJointLimits(angles::normalize_angle(joint_values[i] * angle_multipliers_[i]), i))
775  {
776  return false;
777  }
778  }
779  return true;
780 }
781 
782 bool PR2ArmIK::checkJointLimits(const double& joint_value, const int& joint_num) const
783 {
784  double jv;
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];
789  else
790  jv = angles::normalize_angle(joint_value * angle_multipliers_[joint_num]);
791 
792  return !(jv < min_angles_[joint_num] || jv > max_angles_[joint_num]);
793 }
794 } // namespace pr2_arm_kinematics
x
Definition: pick.py:64
y
Definition: pick.py:65
z
Definition: pick.py:66
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
bool solveCosineEqn(const double &a, const double &b, const double &c, double &soln1, double &soln2)
Definition: pr2_arm_ik.h:91
bool solveQuadratic(const double &a, const double &b, const double &c, double *x1, double *x2)
Definition: pr2_arm_ik.h:61