ur_moveit_plugin.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, Georgia Tech
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 Georgia Tech 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: Kelsey Hawkins */
36 
37 /* Based on orignal source from Willow Garage. License copied below */
38 
39 /*********************************************************************
40 * Software License Agreement (BSD License)
41 *
42 * Copyright (c) 2012, Willow Garage, Inc.
43 * All rights reserved.
44 *
45 * Redistribution and use in source and binary forms, with or without
46 * modification, are permitted provided that the following conditions
47 * are met:
48 *
49 * * Redistributions of source code must retain the above copyright
50 * notice, this list of conditions and the following disclaimer.
51 * * Redistributions in binary form must reproduce the above
52 * copyright notice, this list of conditions and the following
53 * disclaimer in the documentation and/or other materials provided
54 * with the distribution.
55 * * Neither the name of Willow Garage nor the names of its
56 * contributors may be used to endorse or promote products derived
57 * from this software without specific prior written permission.
58 *
59 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
60 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
61 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
62 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
63 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
64 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
65 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
66 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
67 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
68 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
69 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
70 * POSSIBILITY OF SUCH DAMAGE.
71 *********************************************************************/
72 
73 /* Author: Sachin Chitta, David Lu!!, Ugo Cupcic */
74 
75 #include <tf_conversions/tf_kdl.h>
77 
78 // URDF, SRDF
79 #include <urdf_model/model.h>
80 #include <srdfdom/model.h>
81 
83 
84 // UR kin
86 #include <ur_kinematics/ur_kin.h>
87 
88 // register URKinematicsPlugin as a KinematicsBase implementation
91 
92 namespace ur_kinematics
93 {
94 
95  URKinematicsPlugin::URKinematicsPlugin():active_(false) {}
96 
97 void URKinematicsPlugin::getRandomConfiguration(KDL::JntArray &jnt_array, bool lock_redundancy) const
98 {
99  std::vector<double> jnt_array_vector(dimension_, 0.0);
100  state_->setToRandomPositions(joint_model_group_);
101  state_->copyJointGroupPositions(joint_model_group_, &jnt_array_vector[0]);
102  for (std::size_t i = 0; i < dimension_; ++i)
103  {
104  if (lock_redundancy)
105  if (isRedundantJoint(i))
106  continue;
107  jnt_array(i) = jnt_array_vector[i];
108  }
109 }
110 
111 bool URKinematicsPlugin::isRedundantJoint(unsigned int index) const
112 {
113  for (std::size_t j=0; j < redundant_joint_indices_.size(); ++j)
114  if (redundant_joint_indices_[j] == index)
115  return true;
116  return false;
117 }
118 
119 void URKinematicsPlugin::getRandomConfiguration(const KDL::JntArray &seed_state,
120  const std::vector<double> &consistency_limits,
121  KDL::JntArray &jnt_array,
122  bool lock_redundancy) const
123 {
124  std::vector<double> values(dimension_, 0.0);
125  std::vector<double> near(dimension_, 0.0);
126  for (std::size_t i = 0 ; i < dimension_; ++i)
127  near[i] = seed_state(i);
128 
129  // Need to resize the consistency limits to remove mimic joints
130  std::vector<double> consistency_limits_mimic;
131  for(std::size_t i = 0; i < dimension_; ++i)
132  {
133  if(!mimic_joints_[i].active)
134  continue;
135  consistency_limits_mimic.push_back(consistency_limits[i]);
136  }
137 
138  joint_model_group_->getVariableRandomPositionsNearBy(state_->getRandomNumberGenerator(), values, near, consistency_limits_mimic);
139 
140  for (std::size_t i = 0; i < dimension_; ++i)
141  {
142  bool skip = false;
143  if (lock_redundancy)
144  for (std::size_t j = 0; j < redundant_joint_indices_.size(); ++j)
145  if (redundant_joint_indices_[j] == i)
146  {
147  skip = true;
148  break;
149  }
150  if (skip)
151  continue;
152  jnt_array(i) = values[i];
153  }
154 }
155 
156 bool URKinematicsPlugin::checkConsistency(const KDL::JntArray& seed_state,
157  const std::vector<double> &consistency_limits,
158  const KDL::JntArray& solution) const
159 {
160  for (std::size_t i = 0; i < dimension_; ++i)
161  if (fabs(seed_state(i) - solution(i)) > consistency_limits[i])
162  return false;
163  return true;
164 }
165 
166 bool URKinematicsPlugin::initialize(const moveit::core::RobotModel& robot_model,
167  const std::string& group_name,
168  const std::string& base_frame,
169  const std::vector<std::string>& tip_frames,
170  double search_discretization)
171 {
172  storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
173 
174  const robot_model::JointModelGroup* joint_model_group = robot_model_->getJointModelGroup(group_name);
175  if (!joint_model_group)
176  return false;
177 
178  if(!joint_model_group->isChain())
179  {
180  ROS_ERROR_NAMED("kdl","Group '%s' is not a chain", group_name.c_str());
181  return false;
182  }
183  if(!joint_model_group->isSingleDOFJoints())
184  {
185  ROS_ERROR_NAMED("kdl","Group '%s' includes joints that have more than 1 DOF", group_name.c_str());
186  return false;
187  }
188 
189  KDL::Tree kdl_tree;
190 
191  if (!kdl_parser::treeFromUrdfModel(*robot_model.getURDF(), kdl_tree))
192  {
193  ROS_ERROR_NAMED("kdl","Could not initialize tree object");
194  return false;
195  }
196  if (!kdl_tree.getChain(base_frame_, getTipFrame(), kdl_chain_))
197  {
198  ROS_ERROR_NAMED("kdl","Could not initialize chain object");
199  return false;
200  }
201 
202  dimension_ = joint_model_group->getActiveJointModels().size() + joint_model_group->getMimicJointModels().size();
203  for (std::size_t i=0; i < joint_model_group->getJointModels().size(); ++i)
204  {
205  if(joint_model_group->getJointModels()[i]->getType() == moveit::core::JointModel::REVOLUTE || joint_model_group->getJointModels()[i]->getType() == moveit::core::JointModel::PRISMATIC)
206  {
207  ik_chain_info_.joint_names.push_back(joint_model_group->getJointModelNames()[i]);
208  const std::vector<moveit_msgs::JointLimits> &jvec = joint_model_group->getJointModels()[i]->getVariableBoundsMsg();
209  ik_chain_info_.limits.insert(ik_chain_info_.limits.end(), jvec.begin(), jvec.end());
210  }
211  }
212 
213  fk_chain_info_.joint_names = ik_chain_info_.joint_names;
214  fk_chain_info_.limits = ik_chain_info_.limits;
215 
216  if(!joint_model_group->hasLinkModel(getTipFrame()))
217  {
218  ROS_ERROR_NAMED("kdl","Could not find tip name in joint group '%s'", group_name.c_str());
219  return false;
220  }
221  ik_chain_info_.link_names.push_back(getTipFrame());
222  fk_chain_info_.link_names = joint_model_group->getLinkModelNames();
223 
224  joint_min_.resize(ik_chain_info_.limits.size());
225  joint_max_.resize(ik_chain_info_.limits.size());
226 
227  for(unsigned int i=0; i < ik_chain_info_.limits.size(); i++)
228  {
229  joint_min_(i) = ik_chain_info_.limits[i].min_position;
230  joint_max_(i) = ik_chain_info_.limits[i].max_position;
231  }
232 
233  // Get Solver Parameters
234  int max_solver_iterations;
235  double epsilon;
236  bool position_ik;
237 
238  lookupParam("max_solver_iterations", max_solver_iterations, 500);
239  lookupParam("epsilon", epsilon, 1e-5);
240  lookupParam(group_name+"/position_only_ik", position_ik, false);
241 
242  if(position_ik)
243  ROS_INFO_NAMED("kdl","Using position only ik");
244 
245  num_possible_redundant_joints_ = kdl_chain_.getNrOfJoints() - joint_model_group->getMimicJointModels().size() - (position_ik? 3:6);
246 
247  // Check for mimic joints
248  bool has_mimic_joints = joint_model_group->getMimicJointModels().size() > 0;
249  std::vector<unsigned int> redundant_joints_map_index;
250 
251  std::vector<kdl_kinematics_plugin::JointMimic> mimic_joints;
252  unsigned int joint_counter = 0;
253  for (std::size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
254  {
255  const robot_model::JointModel *jm = robot_model_->getJointModel(kdl_chain_.segments[i].getJoint().getName());
256 
257  //first check whether it belongs to the set of active joints in the group
258  if (jm->getMimic() == NULL && jm->getVariableCount() > 0)
259  {
261  mimic_joint.reset(joint_counter);
262  mimic_joint.joint_name = kdl_chain_.segments[i].getJoint().getName();
263  mimic_joint.active = true;
264  mimic_joints.push_back(mimic_joint);
265  ++joint_counter;
266  continue;
267  }
268  if (joint_model_group->hasJointModel(jm->getName()))
269  {
270  if (jm->getMimic() && joint_model_group->hasJointModel(jm->getMimic()->getName()))
271  {
273  mimic_joint.reset(joint_counter);
274  mimic_joint.joint_name = kdl_chain_.segments[i].getJoint().getName();
275  mimic_joint.offset = jm->getMimicOffset();
276  mimic_joint.multiplier = jm->getMimicFactor();
277  mimic_joints.push_back(mimic_joint);
278  continue;
279  }
280  }
281  }
282  for (std::size_t i = 0; i < mimic_joints.size(); ++i)
283  {
284  if(!mimic_joints[i].active)
285  {
286  const robot_model::JointModel* joint_model = joint_model_group->getJointModel(mimic_joints[i].joint_name)->getMimic();
287  for(std::size_t j=0; j < mimic_joints.size(); ++j)
288  {
289  if(mimic_joints[j].joint_name == joint_model->getName())
290  {
291  mimic_joints[i].map_index = mimic_joints[j].map_index;
292  }
293  }
294  }
295  }
296  mimic_joints_ = mimic_joints;
297 
298  // Setup the joint state groups that we need
299  state_.reset(new robot_state::RobotState(robot_model_));
300  state_2_.reset(new robot_state::RobotState(robot_model_));
301 
302  // Store things for when the set of redundant joints may change
303  position_ik_ = position_ik;
304  joint_model_group_ = joint_model_group;
305  max_solver_iterations_ = max_solver_iterations;
306  epsilon_ = epsilon;
307 
308  lookupParam("arm_prefix", arm_prefix_, std::string(""));
309 
310  ur_joint_names_.push_back(arm_prefix_ + "shoulder_pan_joint");
311  ur_joint_names_.push_back(arm_prefix_ + "shoulder_lift_joint");
312  ur_joint_names_.push_back(arm_prefix_ + "elbow_joint");
313  ur_joint_names_.push_back(arm_prefix_ + "wrist_1_joint");
314  ur_joint_names_.push_back(arm_prefix_ + "wrist_2_joint");
315  ur_joint_names_.push_back(arm_prefix_ + "wrist_3_joint");
316 
317  ur_link_names_.push_back(arm_prefix_ + "base_link"); // 0
318  ur_link_names_.push_back(arm_prefix_ + "ur_base_link"); // 1
319  ur_link_names_.push_back(arm_prefix_ + "shoulder_link"); // 2
320  ur_link_names_.push_back(arm_prefix_ + "upper_arm_link"); // 3
321  ur_link_names_.push_back(arm_prefix_ + "forearm_link"); // 4
322  ur_link_names_.push_back(arm_prefix_ + "wrist_1_link"); // 5
323  ur_link_names_.push_back(arm_prefix_ + "wrist_2_link"); // 6
324  ur_link_names_.push_back(arm_prefix_ + "wrist_3_link"); // 7
325  ur_link_names_.push_back(arm_prefix_ + "ee_link"); // 8
326 
327  ur_joint_inds_start_ = getJointIndex(ur_joint_names_[0]);
328 
329  // check to make sure the serial chain is properly defined in the model
330  int cur_ur_joint_ind, last_ur_joint_ind = ur_joint_inds_start_;
331  for(int i=1; i<6; i++) {
332  cur_ur_joint_ind = getJointIndex(ur_joint_names_[i]);
333  if(cur_ur_joint_ind < 0) {
334  ROS_ERROR_NAMED("kdl",
335  "Kin chain provided in model doesn't contain standard UR joint '%s'.",
336  ur_joint_names_[i].c_str());
337  return false;
338  }
339  if(cur_ur_joint_ind != last_ur_joint_ind + 1) {
340  ROS_ERROR_NAMED("kdl",
341  "Kin chain provided in model doesn't have proper serial joint order: '%s'.",
342  ur_joint_names_[i].c_str());
343  return false;
344  }
345  last_ur_joint_ind = cur_ur_joint_ind;
346  }
347  // if successful, the kinematic chain includes a serial chain of the UR joints
348 
349  kdl_tree.getChain(getBaseFrame(), ur_link_names_.front(), kdl_base_chain_);
350  kdl_tree.getChain(ur_link_names_.back(), getTipFrame(), kdl_tip_chain_);
351 
352  // weights for redundant solution selection
353  ik_weights_.resize(6);
354  if(!lookupParam("ik_weights", ik_weights_, ik_weights_)) {
355  ik_weights_[0] = 1.0;
356  ik_weights_[1] = 1.0;
357  ik_weights_[2] = 1.0;
358  ik_weights_[3] = 1.0;
359  ik_weights_[4] = 1.0;
360  ik_weights_[5] = 1.0;
361  }
362 
363  active_ = true;
364  ROS_DEBUG_NAMED("kdl","KDL solver initialized");
365  return true;
366 }
367 
368 bool URKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int> &redundant_joints)
369 {
370  if(num_possible_redundant_joints_ < 0)
371  {
372  ROS_ERROR_NAMED("kdl","This group cannot have redundant joints");
373  return false;
374  }
375  if(redundant_joints.size() > num_possible_redundant_joints_)
376  {
377  ROS_ERROR_NAMED("kdl","This group can only have %d redundant joints", num_possible_redundant_joints_);
378  return false;
379  }
380  std::vector<unsigned int> redundant_joints_map_index;
381  unsigned int counter = 0;
382  for(std::size_t i=0; i < dimension_; ++i)
383  {
384  bool is_redundant_joint = false;
385  for(std::size_t j=0; j < redundant_joints.size(); ++j)
386  {
387  if(i == redundant_joints[j])
388  {
389  is_redundant_joint = true;
390 counter++;
391  break;
392  }
393  }
394  if(!is_redundant_joint)
395  {
396  // check for mimic
397  if(mimic_joints_[i].active)
398  {
399 redundant_joints_map_index.push_back(counter);
400 counter++;
401  }
402  }
403  }
404  for(std::size_t i=0; i < redundant_joints_map_index.size(); ++i)
405  ROS_DEBUG_NAMED("kdl","Redundant joint map index: %d %d", (int) i, (int) redundant_joints_map_index[i]);
406 
407  redundant_joints_map_index_ = redundant_joints_map_index;
408  redundant_joint_indices_ = redundant_joints;
409  return true;
410 }
411 
412 int URKinematicsPlugin::getJointIndex(const std::string &name) const
413 {
414  for (unsigned int i=0; i < ik_chain_info_.joint_names.size(); i++) {
415  if (ik_chain_info_.joint_names[i] == name)
416  return i;
417  }
418  return -1;
419 }
420 
421 int URKinematicsPlugin::getKDLSegmentIndex(const std::string &name) const
422 {
423  int i=0;
424  while (i < (int)kdl_chain_.getNrOfSegments()) {
425  if (kdl_chain_.getSegment(i).getName() == name) {
426  return i+1;
427  }
428  i++;
429  }
430  return -1;
431 }
432 
433 bool URKinematicsPlugin::timedOut(const ros::WallTime &start_time, double duration) const
434 {
435  return ((ros::WallTime::now()-start_time).toSec() >= duration);
436 }
437 
438 bool URKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose,
439  const std::vector<double> &ik_seed_state,
440  std::vector<double> &solution,
441  moveit_msgs::MoveItErrorCodes &error_code,
442  const kinematics::KinematicsQueryOptions &options) const
443 {
444  const IKCallbackFn solution_callback = 0;
445  std::vector<double> consistency_limits;
446 
447  return searchPositionIK(ik_pose,
448  ik_seed_state,
449  default_timeout_,
450  solution,
451  solution_callback,
452  error_code,
453  consistency_limits,
454  options);
455 }
456 
457 bool URKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
458  const std::vector<double> &ik_seed_state,
459  double timeout,
460  std::vector<double> &solution,
461  moveit_msgs::MoveItErrorCodes &error_code,
462  const kinematics::KinematicsQueryOptions &options) const
463 {
464  const IKCallbackFn solution_callback = 0;
465  std::vector<double> consistency_limits;
466 
467  return searchPositionIK(ik_pose,
468  ik_seed_state,
469  timeout,
470  solution,
471  solution_callback,
472  error_code,
473  consistency_limits,
474  options);
475 }
476 
477 bool URKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
478  const std::vector<double> &ik_seed_state,
479  double timeout,
480  const std::vector<double> &consistency_limits,
481  std::vector<double> &solution,
482  moveit_msgs::MoveItErrorCodes &error_code,
483  const kinematics::KinematicsQueryOptions &options) const
484 {
485  const IKCallbackFn solution_callback = 0;
486  return searchPositionIK(ik_pose,
487  ik_seed_state,
488  timeout,
489  solution,
490  solution_callback,
491  error_code,
492  consistency_limits,
493  options);
494 }
495 
496 bool URKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
497  const std::vector<double> &ik_seed_state,
498  double timeout,
499  std::vector<double> &solution,
500  const IKCallbackFn &solution_callback,
501  moveit_msgs::MoveItErrorCodes &error_code,
503 {
504  std::vector<double> consistency_limits;
505  return searchPositionIK(ik_pose,
506  ik_seed_state,
507  timeout,
508  solution,
509  solution_callback,
510  error_code,
511  consistency_limits,
512  options);
513 }
514 
515 bool URKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
516  const std::vector<double> &ik_seed_state,
517  double timeout,
518  const std::vector<double> &consistency_limits,
519  std::vector<double> &solution,
520  const IKCallbackFn &solution_callback,
521  moveit_msgs::MoveItErrorCodes &error_code,
522  const kinematics::KinematicsQueryOptions &options) const
523 {
524  return searchPositionIK(ik_pose,
525  ik_seed_state,
526  timeout,
527  solution,
528  solution_callback,
529  error_code,
530  consistency_limits,
531  options);
532 }
533 
534 typedef std::pair<int, double> idx_double;
535 bool comparator(const idx_double& l, const idx_double& r)
536 { return l.second < r.second; }
537 
538 bool URKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
539  const std::vector<double> &ik_seed_state,
540  double timeout,
541  std::vector<double> &solution,
542  const IKCallbackFn &solution_callback,
543  moveit_msgs::MoveItErrorCodes &error_code,
544  const std::vector<double> &consistency_limits,
545  const kinematics::KinematicsQueryOptions &options) const
546 {
548  if(!active_) {
549  ROS_ERROR_NAMED("kdl","kinematics not active");
550  error_code.val = error_code.NO_IK_SOLUTION;
551  return false;
552  }
553 
554  if(ik_seed_state.size() != dimension_) {
555  ROS_ERROR_STREAM_NAMED("kdl","Seed state must have size " << dimension_ << " instead of size " << ik_seed_state.size());
556  error_code.val = error_code.NO_IK_SOLUTION;
557  return false;
558  }
559 
560  if(!consistency_limits.empty() && consistency_limits.size() != dimension_) {
561  ROS_ERROR_STREAM_NAMED("kdl","Consistency limits be empty or must have size " << dimension_ << " instead of size " << consistency_limits.size());
562  error_code.val = error_code.NO_IK_SOLUTION;
563  return false;
564  }
565 
566  KDL::JntArray jnt_seed_state(dimension_);
567  for(int i=0; i<dimension_; i++)
568  jnt_seed_state(i) = ik_seed_state[i];
569 
570  solution.resize(dimension_);
571 
572  KDL::ChainFkSolverPos_recursive fk_solver_base(kdl_base_chain_);
573  KDL::ChainFkSolverPos_recursive fk_solver_tip(kdl_tip_chain_);
574 
575  KDL::JntArray jnt_pos_test(jnt_seed_state);
576  KDL::JntArray jnt_pos_base(ur_joint_inds_start_);
577  KDL::JntArray jnt_pos_tip(dimension_ - 6 - ur_joint_inds_start_);
578  KDL::Frame pose_base, pose_tip;
579 
580  KDL::Frame kdl_ik_pose;
581  KDL::Frame kdl_ik_pose_ur_chain;
582  double homo_ik_pose[4][4];
583  double q_ik_sols[8][6]; // maximum of 8 IK solutions
584  uint16_t num_sols;
585 
586  while(1) {
587  if(timedOut(n1, timeout)) {
588  ROS_DEBUG_NAMED("kdl","IK timed out");
589  error_code.val = error_code.TIMED_OUT;
590  return false;
591  }
592 
594  // find transformation from robot base to UR base and UR tip to robot tip
595  for(uint32_t i=0; i<jnt_pos_base.rows(); i++)
596  jnt_pos_base(i) = jnt_pos_test(i);
597  for(uint32_t i=0; i<jnt_pos_tip.rows(); i++)
598  jnt_pos_tip(i) = jnt_pos_test(i + ur_joint_inds_start_ + 6);
599  for(uint32_t i=0; i<jnt_seed_state.rows(); i++)
600  solution[i] = jnt_pos_test(i);
601 
602  if(fk_solver_base.JntToCart(jnt_pos_base, pose_base) < 0) {
603  ROS_ERROR_NAMED("kdl", "Could not compute FK for base chain");
604  return false;
605  }
606 
607  if(fk_solver_tip.JntToCart(jnt_pos_tip, pose_tip) < 0) {
608  ROS_ERROR_NAMED("kdl", "Could not compute FK for tip chain");
609  return false;
610  }
612 
614  // Convert into query for analytic solver
615  tf::poseMsgToKDL(ik_pose, kdl_ik_pose);
616  kdl_ik_pose_ur_chain = pose_base.Inverse() * kdl_ik_pose * pose_tip.Inverse();
617 
618  kdl_ik_pose_ur_chain.Make4x4((double*) homo_ik_pose);
619 #if KDL_OLD_BUG_FIX
620  // in older versions of KDL, setting this flag might be necessary
621  for(int i=0; i<3; i++) homo_ik_pose[i][3] *= 1000; // strange KDL fix
622 #endif
623 
625  // Do the analytic IK
626  num_sols = inverse((double*) homo_ik_pose, (double*) q_ik_sols,
627  jnt_pos_test(ur_joint_inds_start_+5));
628 
629 
630  uint16_t num_valid_sols;
631  std::vector< std::vector<double> > q_ik_valid_sols;
632  for(uint16_t i=0; i<num_sols; i++)
633  {
634  bool valid = true;
635  std::vector< double > valid_solution;
636  valid_solution.assign(6,0.0);
637 
638  for(uint16_t j=0; j<6; j++)
639  {
640  if((q_ik_sols[i][j] <= ik_chain_info_.limits[j].max_position) && (q_ik_sols[i][j] >= ik_chain_info_.limits[j].min_position))
641  {
642  valid_solution[j] = q_ik_sols[i][j];
643  valid = true;
644  continue;
645  }
646  else if ((q_ik_sols[i][j] > ik_chain_info_.limits[j].max_position) && (q_ik_sols[i][j]-2*M_PI > ik_chain_info_.limits[j].min_position))
647  {
648  valid_solution[j] = q_ik_sols[i][j]-2*M_PI;
649  valid = true;
650  continue;
651  }
652  else if ((q_ik_sols[i][j] < ik_chain_info_.limits[j].min_position) && (q_ik_sols[i][j]+2*M_PI < ik_chain_info_.limits[j].max_position))
653  {
654  valid_solution[j] = q_ik_sols[i][j]+2*M_PI;
655  valid = true;
656  continue;
657  }
658  else
659  {
660  valid = false;
661  break;
662  }
663  }
664 
665  if(valid)
666  {
667  q_ik_valid_sols.push_back(valid_solution);
668  }
669  }
670 
671 
672  // use weighted absolute deviations to determine the solution closest the seed state
673  std::vector<idx_double> weighted_diffs;
674  for(uint16_t i=0; i<q_ik_valid_sols.size(); i++) {
675  double cur_weighted_diff = 0;
676  for(uint16_t j=0; j<6; j++) {
677  // solution violates the consistency_limits, throw it out
678  double abs_diff = std::fabs(ik_seed_state[ur_joint_inds_start_+j] - q_ik_valid_sols[i][j]);
679  if(!consistency_limits.empty() && abs_diff > consistency_limits[ur_joint_inds_start_+j]) {
680  cur_weighted_diff = std::numeric_limits<double>::infinity();
681  break;
682  }
683  cur_weighted_diff += ik_weights_[j] * abs_diff;
684  }
685  weighted_diffs.push_back(idx_double(i, cur_weighted_diff));
686  }
687 
688  std::sort(weighted_diffs.begin(), weighted_diffs.end(), comparator);
689 
690 #if 0
691  printf("start\n");
692  printf(" q %1.2f, %1.2f, %1.2f, %1.2f, %1.2f, %1.2f\n", ik_seed_state[1], ik_seed_state[2], ik_seed_state[3], ik_seed_state[4], ik_seed_state[5], ik_seed_state[6]);
693  for(uint16_t i=0; i<weighted_diffs.size(); i++) {
694  int cur_idx = weighted_diffs[i].first;
695  printf("diff %f, i %d, q %1.2f, %1.2f, %1.2f, %1.2f, %1.2f, %1.2f\n", weighted_diffs[i].second, cur_idx, q_ik_valid_sols[cur_idx][0], q_ik_valid_sols[cur_idx][1], q_ik_valid_sols[cur_idx][2], q_ik_valid_sols[cur_idx][3], q_ik_valid_sols[cur_idx][4], q_ik_valid_sols[cur_idx][5]);
696  }
697  printf("end\n");
698 #endif
699 
700  for(uint16_t i=0; i<weighted_diffs.size(); i++) {
701  if(weighted_diffs[i].second == std::numeric_limits<double>::infinity()) {
702  // rest are infinity, no more feasible solutions
703  break;
704  }
705 
706  // copy the best solution to the output
707  int cur_idx = weighted_diffs[i].first;
708  solution = q_ik_valid_sols[cur_idx];
709 
710  // see if this solution passes the callback function test
711  if(!solution_callback.empty())
712  solution_callback(ik_pose, solution, error_code);
713  else
714  error_code.val = error_code.SUCCESS;
715 
716  if(error_code.val == error_code.SUCCESS) {
717 #if 0
718  std::vector<std::string> fk_link_names;
719  fk_link_names.push_back(ur_link_names_.back());
720  std::vector<geometry_msgs::Pose> fk_poses;
721  getPositionFK(fk_link_names, solution, fk_poses);
722  KDL::Frame kdl_fk_pose;
723  tf::poseMsgToKDL(fk_poses[0], kdl_fk_pose);
724  printf("FK(solution) - pose \n");
725  for(int i=0; i<4; i++) {
726  for(int j=0; j<4; j++)
727  printf("%1.6f ", kdl_fk_pose(i, j)-kdl_ik_pose(i, j));
728  printf("\n");
729  }
730 #endif
731  return true;
732  }
733  }
734  // none of the solutions were both consistent and passed the solution callback
735 
736  if(options.lock_redundant_joints) {
737  ROS_DEBUG_NAMED("kdl","Will not pertubate redundant joints to find solution");
738  break;
739  }
740 
741  if(dimension_ == 6) {
742  ROS_DEBUG_NAMED("kdl","No other joints to pertubate, cannot find solution");
743  break;
744  }
745 
746  // randomly pertubate other joints and try again
747  if(!consistency_limits.empty()) {
748  getRandomConfiguration(jnt_seed_state, consistency_limits, jnt_pos_test, false);
749  } else {
750  getRandomConfiguration(jnt_pos_test, false);
751  }
752  }
753 
754  ROS_DEBUG_NAMED("kdl","An IK that satisifes the constraints and is collision free could not be found");
755  error_code.val = error_code.NO_IK_SOLUTION;
756  return false;
757 }
758 
759 bool URKinematicsPlugin::getPositionFK(const std::vector<std::string> &link_names,
760  const std::vector<double> &joint_angles,
761  std::vector<geometry_msgs::Pose> &poses) const
762 {
764  if(!active_)
765  {
766  ROS_ERROR_NAMED("kdl","kinematics not active");
767  return false;
768  }
769  poses.resize(link_names.size());
770  if(joint_angles.size() != dimension_)
771  {
772  ROS_ERROR_NAMED("kdl","Joint angles vector must have size: %d",dimension_);
773  return false;
774  }
775 
776  KDL::Frame p_out;
777  geometry_msgs::PoseStamped pose;
778  tf::Stamped<tf::Pose> tf_pose;
779 
780  KDL::JntArray jnt_pos_in(dimension_);
781  for(unsigned int i=0; i < dimension_; i++)
782  {
783  jnt_pos_in(i) = joint_angles[i];
784  }
785 
786  KDL::ChainFkSolverPos_recursive fk_solver(kdl_chain_);
787 
788  bool valid = true;
789  for(unsigned int i=0; i < poses.size(); i++)
790  {
791  ROS_DEBUG_NAMED("kdl","End effector index: %d",getKDLSegmentIndex(link_names[i]));
792  if(fk_solver.JntToCart(jnt_pos_in,p_out,getKDLSegmentIndex(link_names[i])) >=0)
793  {
794  tf::poseKDLToMsg(p_out,poses[i]);
795  }
796  else
797  {
798  ROS_ERROR_NAMED("kdl","Could not compute FK for %s",link_names[i].c_str());
799  valid = false;
800  }
801  }
802  return valid;
803 }
804 
805 const std::vector<std::string>& URKinematicsPlugin::getJointNames() const
806 {
807  return ik_chain_info_.joint_names;
808 }
809 
810 const std::vector<std::string>& URKinematicsPlugin::getLinkNames() const
811 {
812  return ik_chain_info_.link_names;
813 }
814 
815 } // namespace
kdl_kinematics_plugin::JointMimic
epsilon
double epsilon
duration
std::chrono::system_clock::duration duration
ur_moveit_plugin.h
moveit::core::RobotModel::getURDF
const urdf::ModelInterfaceSharedPtr & getURDF() const
rdf_loader.h
moveit::core::RobotModel
kdl_kinematics_plugin::JointMimic::reset
void reset(unsigned int index)
tf::poseMsgToKDL
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
kdl_kinematics_plugin::JointMimic::offset
double offset
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
ur_kin.h
moveit::core::JointModel::PRISMATIC
PRISMATIC
kinematics::KinematicsBase::IKCallbackFn
boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)> IKCallbackFn
kdl_parser::treeFromUrdfModel
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
moveit::core::JointModel::REVOLUTE
REVOLUTE
tf::Stamped
kdl_kinematics_plugin::JointMimic::active
bool active
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
kinematics::KinematicsBase
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
ros::WallTime::now
static WallTime now()
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
model.h
ur_kinematics::comparator
bool comparator(const idx_double &l, const idx_double &r)
Definition: ur_moveit_plugin.cpp:599
class_loader.hpp
kdl_kinematics_plugin::JointMimic::joint_name
std::string joint_name
ros::WallTime
ur_kinematics::URKinematicsPlugin
Specific implementation of kinematics using KDL. This version can be used with any robot.
Definition: ur_moveit_plugin.h:173
r
S r
ur_kinematics
Definition: ur_kin.h:58
kdl_parser.hpp
kinematics::KinematicsQueryOptions::lock_redundant_joints
bool lock_redundant_joints
ur_kinematics::URKinematicsPlugin::URKinematicsPlugin
URKinematicsPlugin()
Default constructor.
Definition: ur_moveit_plugin.cpp:159
values
std::vector< double > values
kinematics::KinematicsQueryOptions
M_PI
#define M_PI
tf_kdl.h
ur_kinematics::idx_double
std::pair< int, double > idx_double
Definition: ur_moveit_plugin.cpp:598
CLASS_LOADER_REGISTER_CLASS
CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::AddIterativeSplineParameterization, planning_request_adapter::PlanningRequestAdapter)
ur_kinematics::inverse
int inverse(const double *T, double *q_sols, double q6_des=0.0)
Definition: ur_kin.cpp:267
tf::poseKDLToMsg
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
kdl_kinematics_plugin::JointMimic::multiplier
double multiplier


ur_kinematics
Author(s): Kelsey Hawkins
autogenerated on Tue May 13 2025 02:43:05