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


ur_kinematics
Author(s): Kelsey Hawkins
autogenerated on Sun Nov 24 2019 03:36:27