kr6_r900_workspace_manipulator_ikfast_moveit_plugin.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Dave Coleman, CU Boulder; Jeremy Zoss, SwRI; David Butterworth, KAIST; Mathias Lüdtke, Fraunhofer
6  *IPA
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above copyright
16  * notice, this list of conditions and the following disclaimer in the
17  * documentation and/or other materials provided with the distribution.
18  * * Neither the name of the all of the author's companies nor the names of its
19  * contributors may be used to endorse or promote products derived from
20  * this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
23  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
24  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
25  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
26  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
27  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
28  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
29  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
30  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
31  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  *********************************************************************/
35 
36 /*
37  * IKFast Plugin Template for moveit
38  *
39  * AUTO-GENERATED by create_ikfast_moveit_plugin.py in arm_kinematics_tools
40  * You should run create_ikfast_moveit_plugin.py to generate your own plugin.
41  *
42  * Creates a kinematics plugin using the output of IKFast from OpenRAVE.
43  * This plugin and the move_group node can be used as a general
44  * kinematics service, from within the moveit planning environment, or in
45  * your own ROS node.
46  *
47  */
48 
49 #include <ros/ros.h>
51 #include <urdf/model.h>
52 #include <tf_conversions/tf_kdl.h>
53 
54 // Need a floating point tolerance when checking joint limits, in case the joint starts at limit
55 const double LIMIT_TOLERANCE = .0000001;
58 {
61 };
62 
64 {
65 #define IKFAST_NO_MAIN // Don't include main() from IKFast
66 
73 {
74  IKP_None = 0,
75  IKP_Transform6D = 0x67000001,
76  IKP_Rotation3D = 0x34000002,
77  IKP_Translation3D = 0x33000003,
78  IKP_Direction3D = 0x23000004,
79  IKP_Ray4D = 0x46000005,
80  IKP_Lookat3D = 0x23000006,
82  IKP_TranslationXY2D = 0x22000008,
86  IKP_TranslationLocalGlobal6D = 0x3600000a,
89 
91  IKP_TranslationYAxisAngle4D = 0x4400000c,
97 
101  IKP_TranslationYAxisAngleXNorm4D = 0x4400000f,
105  IKP_TranslationZAxisAngleYNorm4D = 0x44000010,
109 
114 
116  0x00008000,
133 
134  IKP_UniqueIdMask = 0x0000ffff,
135  IKP_CustomDataBit = 0x00010000,
136 };
138 
139 // struct for storing and sorting solutions
141 {
142  std::vector<double> value;
144 
145  bool operator<(const LimitObeyingSol& a) const
146  {
147  return dist_from_seed < a.dist_from_seed;
148  }
149 };
150 
151 // Code generated by IKFast56/61
153 
155 {
156 protected:
157  std::vector<std::string> joint_names_;
158  std::vector<double> joint_min_vector_;
159  std::vector<double> joint_max_vector_;
160  std::vector<bool> joint_has_limits_vector_;
161  std::vector<std::string> link_names_;
162  size_t num_joints_;
163  std::vector<int> free_params_;
164  bool active_; // Internal variable that indicates whether solvers are configured and ready
165 
166  const std::vector<std::string>& getJointNames() const
167  {
168  return joint_names_;
169  }
170  const std::vector<std::string>& getLinkNames() const
171  {
172  return link_names_;
173  }
175 public:
179  IKFastKinematicsPlugin() : active_(false)
180  {
181  srand(time(NULL));
182  supported_methods_.push_back(kinematics::DiscretizationMethods::NO_DISCRETIZATION);
183  supported_methods_.push_back(kinematics::DiscretizationMethods::ALL_DISCRETIZED);
184  supported_methods_.push_back(kinematics::DiscretizationMethods::ALL_RANDOM_SAMPLED);
185  }
186 
196  // Returns the IK solution that is within joint limits closest to ik_seed_state
197  bool getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
198  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
200 
216  bool getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
217  std::vector<std::vector<double>>& solutions, kinematics::KinematicsResult& result,
218  const kinematics::KinematicsQueryOptions& options) const;
219 
228  bool searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
229  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
231 
241  bool searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
242  const std::vector<double>& consistency_limits, std::vector<double>& solution,
243  moveit_msgs::MoveItErrorCodes& error_code,
245 
254  bool searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
255  std::vector<double>& solution, const IKCallbackFn& solution_callback,
256  moveit_msgs::MoveItErrorCodes& error_code,
258 
269  bool searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
270  const std::vector<double>& consistency_limits, std::vector<double>& solution,
271  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
273 
282  bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
283  std::vector<geometry_msgs::Pose>& poses) const;
284 
294  void setSearchDiscretization(const std::map<int, double>& discretization);
295 
299  bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices);
300 
301 protected:
302  bool initialize(const std::string& robot_description, const std::string& group_name, const std::string& base_name,
303  const std::string& tip_name, double search_discretization);
304 
309  int solve(KDL::Frame& pose_frame, const std::vector<double>& vfree, IkSolutionList<IkReal>& solutions) const;
310 
314  void getSolution(const IkSolutionList<IkReal>& solutions, int i, std::vector<double>& solution) const;
315 
319  void getSolution(const IkSolutionList<IkReal>& solutions, const std::vector<double>& ik_seed_state, int i,
320  std::vector<double>& solution) const;
321 
322  double harmonize(const std::vector<double>& ik_seed_state, std::vector<double>& solution) const;
323  // void getOrderedSolutions(const std::vector<double> &ik_seed_state, std::vector<std::vector<double> >& solslist);
324  void getClosestSolution(const IkSolutionList<IkReal>& solutions, const std::vector<double>& ik_seed_state,
325  std::vector<double>& solution) const;
326  void fillFreeParams(int count, int* array);
327  bool getCount(int& count, const int& max_count, const int& min_count) const;
328 
335  bool sampleRedundantJoint(kinematics::DiscretizationMethod method, std::vector<double>& sampled_joint_vals) const;
336 
337 }; // end class
338 
339 bool IKFastKinematicsPlugin::initialize(const std::string& robot_description, const std::string& group_name,
340  const std::string& base_name, const std::string& tip_name,
341  double search_discretization)
342 {
343  setValues(robot_description, group_name, base_name, tip_name, search_discretization);
344 
345  ros::NodeHandle node_handle("~/" + group_name);
346 
347  std::string robot;
348  lookupParam("robot", robot, std::string());
349 
350  // IKFast56/61
351  fillFreeParams(GetNumFreeParameters(), GetFreeParameters());
352  num_joints_ = GetNumJoints();
353 
354  if (free_params_.size() > 1)
355  {
356  ROS_FATAL("Only one free joint parameter supported!");
357  return false;
358  }
359  else if (free_params_.size() == 1)
360  {
361  redundant_joint_indices_.clear();
362  redundant_joint_indices_.push_back(free_params_[0]);
363  KinematicsBase::setSearchDiscretization(DEFAULT_SEARCH_DISCRETIZATION);
364  }
365 
366  urdf::Model robot_model;
367  std::string xml_string;
369  std::string urdf_xml, full_urdf_xml;
370  lookupParam("urdf_xml", urdf_xml, robot_description);
371  node_handle.searchParam(urdf_xml, full_urdf_xml);
373  ROS_DEBUG_NAMED("ikfast", "Reading xml file from parameter server");
374  if (!node_handle.getParam(full_urdf_xml, xml_string))
375  {
376  ROS_FATAL_NAMED("ikfast", "Could not load the xml from parameter server: %s", urdf_xml.c_str());
377  return false;
378  }
380  robot_model.initString(xml_string);
382  ROS_DEBUG_STREAM_NAMED("ikfast", "Reading joints and links from URDF");
383 
384  urdf::LinkConstSharedPtr link = robot_model.getLink(getTipFrame());
385  while (link->name != base_frame_ && joint_names_.size() <= num_joints_)
386  {
387  ROS_DEBUG_NAMED("ikfast", "Link %s", link->name.c_str());
388  link_names_.push_back(link->name);
389  urdf::JointSharedPtr joint = link->parent_joint;
390  if (joint)
391  {
392  if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
393  {
394  ROS_DEBUG_STREAM_NAMED("ikfast", "Adding joint " << joint->name);
395 
396  joint_names_.push_back(joint->name);
397  float lower, upper;
398  int hasLimits;
399  if (joint->type != urdf::Joint::CONTINUOUS)
400  {
401  if (joint->safety)
402  {
403  lower = joint->safety->soft_lower_limit;
404  upper = joint->safety->soft_upper_limit;
405  }
406  else
407  {
408  lower = joint->limits->lower;
409  upper = joint->limits->upper;
410  }
411  hasLimits = 1;
412  }
413  else
414  {
415  lower = -M_PI;
416  upper = M_PI;
417  hasLimits = 0;
418  }
419  if (hasLimits)
420  {
421  joint_has_limits_vector_.push_back(true);
422  joint_min_vector_.push_back(lower);
423  joint_max_vector_.push_back(upper);
424  }
425  else
426  {
427  joint_has_limits_vector_.push_back(false);
428  joint_min_vector_.push_back(-M_PI);
429  joint_max_vector_.push_back(M_PI);
430  }
431  }
432  }
433  else
434  {
435  ROS_WARN_NAMED("ikfast", "no joint corresponding to %s", link->name.c_str());
436  }
437  link = link->getParent();
438  }
439 
440  if (joint_names_.size() != num_joints_)
441  {
442  ROS_FATAL_STREAM_NAMED("ikfast", "Joint numbers mismatch: URDF has " << joint_names_.size() << " and IKFast has "
443  << num_joints_);
444  return false;
445  }
446 
447  std::reverse(link_names_.begin(), link_names_.end());
448  std::reverse(joint_names_.begin(), joint_names_.end());
449  std::reverse(joint_min_vector_.begin(), joint_min_vector_.end());
450  std::reverse(joint_max_vector_.begin(), joint_max_vector_.end());
451  std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end());
452 
453  for (size_t i = 0; i < num_joints_; ++i)
454  ROS_DEBUG_STREAM_NAMED("ikfast", joint_names_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i]
455  << " " << joint_has_limits_vector_[i]);
456 
457  active_ = true;
458  return true;
459 }
460 
461 void IKFastKinematicsPlugin::setSearchDiscretization(const std::map<int, double>& discretization)
462 {
463  if (discretization.empty())
464  {
465  ROS_ERROR("The 'discretization' map is empty");
466  return;
467  }
468 
469  if (redundant_joint_indices_.empty())
470  {
471  ROS_ERROR_STREAM("This group's solver doesn't support redundant joints");
472  return;
473  }
474 
475  if (discretization.begin()->first != redundant_joint_indices_[0])
476  {
477  std::string redundant_joint = joint_names_[free_params_[0]];
478  ROS_ERROR_STREAM("Attempted to discretize a non-redundant joint "
479  << discretization.begin()->first << ", only joint '" << redundant_joint << "' with index "
480  << redundant_joint_indices_[0] << " is redundant.");
481  return;
482  }
483 
484  if (discretization.begin()->second <= 0.0)
485  {
486  ROS_ERROR_STREAM("Discretization can not takes values that are <= 0");
487  return;
488  }
489 
490  redundant_joint_discretization_.clear();
491  redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second;
492 }
493 
494 bool IKFastKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices)
495 {
496  ROS_ERROR_STREAM("Changing the redundant joints isn't permitted by this group's solver ");
497  return false;
498 }
499 
500 int IKFastKinematicsPlugin::solve(KDL::Frame& pose_frame, const std::vector<double>& vfree,
501  IkSolutionList<IkReal>& solutions) const
502 {
503  // IKFast56/61
504  solutions.Clear();
505 
506  double trans[3];
507  trans[0] = pose_frame.p[0]; //-.18;
508  trans[1] = pose_frame.p[1];
509  trans[2] = pose_frame.p[2];
510 
511  KDL::Rotation mult;
512  KDL::Vector direction;
513 
514  switch (GetIkType())
515  {
516  case IKP_Transform6D:
517  case IKP_Translation3D:
518  // For **Transform6D**, eerot is 9 values for the 3x3 rotation matrix. For **Translation3D**, these are ignored.
519 
520  mult = pose_frame.M;
521 
522  double vals[9];
523  vals[0] = mult(0, 0);
524  vals[1] = mult(0, 1);
525  vals[2] = mult(0, 2);
526  vals[3] = mult(1, 0);
527  vals[4] = mult(1, 1);
528  vals[5] = mult(1, 2);
529  vals[6] = mult(2, 0);
530  vals[7] = mult(2, 1);
531  vals[8] = mult(2, 2);
532 
533  // IKFast56/61
534  ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
535  return solutions.GetNumSolutions();
536 
537  case IKP_Direction3D:
538  case IKP_Ray4D:
540  // For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target
541  // direction.
542 
543  direction = pose_frame.M * KDL::Vector(0, 0, 1);
544  ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
545  return solutions.GetNumSolutions();
546 
550  // For **TranslationXAxisAngle4D**, **TranslationYAxisAngle4D**, and **TranslationZAxisAngle4D**, the first value
551  // represents the angle.
552  ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
553  return 0;
554 
556  // For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end
557  // effector coordinate system.
558  ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
559  return 0;
560 
561  case IKP_Rotation3D:
562  case IKP_Lookat3D:
563  case IKP_TranslationXY2D:
568  ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
569  return 0;
570 
571  default:
572  ROS_ERROR_NAMED("ikfast", "Unknown IkParameterizationType! Was the solver generated with an incompatible version "
573  "of Openrave?");
574  return 0;
575  }
576 }
577 
579  std::vector<double>& solution) const
580 {
581  solution.clear();
582  solution.resize(num_joints_);
583 
584  // IKFast56/61
585  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
586  std::vector<IkReal> vsolfree(sol.GetFree().size());
587  sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : NULL);
588 
589  // std::cout << "solution " << i << ":" ;
590  // for(int j=0;j<num_joints_; ++j)
591  // std::cout << " " << solution[j];
592  // std::cout << std::endl;
593 
594  // ROS_ERROR("%f %d",solution[2],vsolfree.size());
595 }
596 
598  const std::vector<double>& ik_seed_state, int i,
599  std::vector<double>& solution) const
600 {
601  solution.clear();
602  solution.resize(num_joints_);
603 
604  // IKFast56/61
605  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
606  std::vector<IkReal> vsolfree(sol.GetFree().size());
607  sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : NULL);
608 
609  // rotate joints by +/-360° where it is possible and useful
610  for (std::size_t i = 0; i < num_joints_; ++i)
611  {
612  if (joint_has_limits_vector_[i])
613  {
614  double signed_distance = solution[i] - ik_seed_state[i];
615  while (signed_distance > M_PI && solution[i] - 2 * M_PI > (joint_min_vector_[i] - LIMIT_TOLERANCE))
616  {
617  signed_distance -= 2 * M_PI;
618  solution[i] -= 2 * M_PI;
619  }
620  while (signed_distance < -M_PI && solution[i] + 2 * M_PI < (joint_max_vector_[i] + LIMIT_TOLERANCE))
621  {
622  signed_distance += 2 * M_PI;
623  solution[i] += 2 * M_PI;
624  }
625  }
626  }
627 }
628 
629 double IKFastKinematicsPlugin::harmonize(const std::vector<double>& ik_seed_state, std::vector<double>& solution) const
630 {
631  double dist_sqr = 0;
632  std::vector<double> ss = ik_seed_state;
633  for (size_t i = 0; i < ik_seed_state.size(); ++i)
634  {
635  while (ss[i] > 2 * M_PI)
636  {
637  ss[i] -= 2 * M_PI;
638  }
639  while (ss[i] < 2 * M_PI)
640  {
641  ss[i] += 2 * M_PI;
642  }
643  while (solution[i] > 2 * M_PI)
644  {
645  solution[i] -= 2 * M_PI;
646  }
647  while (solution[i] < 2 * M_PI)
648  {
649  solution[i] += 2 * M_PI;
650  }
651  dist_sqr += fabs(ik_seed_state[i] - solution[i]);
652  }
653  return dist_sqr;
654 }
655 
656 // void IKFastKinematicsPlugin::getOrderedSolutions(const std::vector<double> &ik_seed_state,
657 // std::vector<std::vector<double> >& solslist)
658 // {
659 // std::vector<double>
660 // double mindist = 0;
661 // int minindex = -1;
662 // std::vector<double> sol;
663 // for(size_t i=0;i<solslist.size();++i){
664 // getSolution(i,sol);
665 // double dist = harmonize(ik_seed_state, sol);
666 // //std::cout << "dist[" << i << "]= " << dist << std::endl;
667 // if(minindex == -1 || dist<mindist){
668 // minindex = i;
669 // mindist = dist;
670 // }
671 // }
672 // if(minindex >= 0){
673 // getSolution(minindex,solution);
674 // harmonize(ik_seed_state, solution);
675 // index = minindex;
676 // }
677 // }
678 
680  const std::vector<double>& ik_seed_state,
681  std::vector<double>& solution) const
682 {
683  double mindist = DBL_MAX;
684  int minindex = -1;
685  std::vector<double> sol;
686 
687  // IKFast56/61
688  for (size_t i = 0; i < solutions.GetNumSolutions(); ++i)
689  {
690  getSolution(solutions, i, sol);
691  double dist = harmonize(ik_seed_state, sol);
692  ROS_INFO_STREAM_NAMED("ikfast", "Dist " << i << " dist " << dist);
693  // std::cout << "dist[" << i << "]= " << dist << std::endl;
694  if (minindex == -1 || dist < mindist)
695  {
696  minindex = i;
697  mindist = dist;
698  }
699  }
700  if (minindex >= 0)
701  {
702  getSolution(solutions, minindex, solution);
703  harmonize(ik_seed_state, solution);
704  }
705 }
706 
707 void IKFastKinematicsPlugin::fillFreeParams(int count, int* array)
708 {
709  free_params_.clear();
710  for (int i = 0; i < count; ++i)
711  free_params_.push_back(array[i]);
712 }
713 
714 bool IKFastKinematicsPlugin::getCount(int& count, const int& max_count, const int& min_count) const
715 {
716  if (count > 0)
717  {
718  if (-count >= min_count)
719  {
720  count = -count;
721  return true;
722  }
723  else if (count + 1 <= max_count)
724  {
725  count = count + 1;
726  return true;
727  }
728  else
729  {
730  return false;
731  }
732  }
733  else
734  {
735  if (1 - count <= max_count)
736  {
737  count = 1 - count;
738  return true;
739  }
740  else if (count - 1 >= min_count)
741  {
742  count = count - 1;
743  return true;
744  }
745  else
746  return false;
747  }
748 }
749 
750 bool IKFastKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
751  const std::vector<double>& joint_angles,
752  std::vector<geometry_msgs::Pose>& poses) const
753 {
754  if (GetIkType() != IKP_Transform6D)
755  {
756  // ComputeFk() is the inverse function of ComputeIk(), so the format of
757  // eerot differs depending on IK type. The Transform6D IK type is the only
758  // one for which a 3x3 rotation matrix is returned, which means we can only
759  // compute FK for that IK type.
760  ROS_ERROR_NAMED("ikfast", "Can only compute FK for Transform6D IK type!");
761  return false;
762  }
763 
764  KDL::Frame p_out;
765  if (link_names.size() == 0)
766  {
767  ROS_WARN_STREAM_NAMED("ikfast", "Link names with nothing");
768  return false;
769  }
770 
771  if (link_names.size() != 1 || link_names[0] != getTipFrame())
772  {
773  ROS_ERROR_NAMED("ikfast", "Can compute FK for %s only", getTipFrame().c_str());
774  return false;
775  }
776 
777  bool valid = true;
778 
779  IkReal eerot[9], eetrans[3];
780  IkReal angles[joint_angles.size()];
781  for (unsigned char i = 0; i < joint_angles.size(); i++)
782  angles[i] = joint_angles[i];
783 
784  // IKFast56/61
785  ComputeFk(angles, eetrans, eerot);
786 
787  for (int i = 0; i < 3; ++i)
788  p_out.p.data[i] = eetrans[i];
789 
790  for (int i = 0; i < 9; ++i)
791  p_out.M.data[i] = eerot[i];
792 
793  poses.resize(1);
794  tf::poseKDLToMsg(p_out, poses[0]);
795 
796  return valid;
797 }
798 
799 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
800  const std::vector<double>& ik_seed_state, double timeout,
801  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
802  const kinematics::KinematicsQueryOptions& options) const
803 {
804  const IKCallbackFn solution_callback = 0;
805  std::vector<double> consistency_limits;
806 
807  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
808  options);
809 }
810 
811 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
812  const std::vector<double>& ik_seed_state, double timeout,
813  const std::vector<double>& consistency_limits,
814  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
815  const kinematics::KinematicsQueryOptions& options) const
816 {
817  const IKCallbackFn solution_callback = 0;
818  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
819  options);
820 }
821 
822 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
823  const std::vector<double>& ik_seed_state, double timeout,
824  std::vector<double>& solution, const IKCallbackFn& solution_callback,
825  moveit_msgs::MoveItErrorCodes& error_code,
826  const kinematics::KinematicsQueryOptions& options) const
827 {
828  std::vector<double> consistency_limits;
829  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
830  options);
831 }
832 
833 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
834  const std::vector<double>& ik_seed_state, double timeout,
835  const std::vector<double>& consistency_limits,
836  std::vector<double>& solution, const IKCallbackFn& solution_callback,
837  moveit_msgs::MoveItErrorCodes& error_code,
838  const kinematics::KinematicsQueryOptions& options) const
839 {
840  ROS_DEBUG_STREAM_NAMED("ikfast", "searchPositionIK");
841 
843  SEARCH_MODE search_mode = OPTIMIZE_MAX_JOINT;
844 
845  // Check if there are no redundant joints
846  if (free_params_.size() == 0)
847  {
848  ROS_DEBUG_STREAM_NAMED("ikfast", "No need to search since no free params/redundant joints");
849 
850  std::vector<geometry_msgs::Pose> ik_poses(1, ik_pose);
851  std::vector<std::vector<double>> solutions;
852  kinematics::KinematicsResult kinematic_result;
853  // Find all IK solution within joint limits
854  if (!getPositionIK(ik_poses, ik_seed_state, solutions, kinematic_result, options))
855  {
856  ROS_DEBUG_STREAM_NAMED("ikfast", "No solution whatsoever");
857  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
858  return false;
859  }
860 
861  // sort solutions by their distance to the seed
862  std::vector<LimitObeyingSol> solutions_obey_limits;
863  for (std::size_t i = 0; i < solutions.size(); ++i)
864  {
865  double dist_from_seed = 0.0;
866  for (std::size_t j = 0; j < ik_seed_state.size(); ++j)
867  {
868  dist_from_seed += fabs(ik_seed_state[j] - solutions[i][j]);
869  }
870 
871  solutions_obey_limits.push_back({ solutions[i], dist_from_seed });
872  }
873  std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
874 
875  // check for collisions if a callback is provided
876  if (!solution_callback.empty())
877  {
878  for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i)
879  {
880  solution_callback(ik_pose, solutions_obey_limits[i].value, error_code);
881  if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
882  {
883  solution = solutions_obey_limits[i].value;
884  ROS_DEBUG_STREAM_NAMED("ikfast", "Solution passes callback");
885  return true;
886  }
887  }
888 
889  ROS_DEBUG_STREAM_NAMED("ikfast", "Solution has error code " << error_code);
890  return false;
891  }
892  else
893  {
894  solution = solutions_obey_limits[0].value;
895  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
896  return true; // no collision check callback provided
897  }
898  }
899 
900  // -------------------------------------------------------------------------------------------------
901  // Error Checking
902  if (!active_)
903  {
904  ROS_ERROR_STREAM_NAMED("ikfast", "Kinematics not active");
905  error_code.val = error_code.NO_IK_SOLUTION;
906  return false;
907  }
908 
909  if (ik_seed_state.size() != num_joints_)
910  {
911  ROS_ERROR_STREAM_NAMED("ikfast", "Seed state must have size " << num_joints_ << " instead of size "
912  << ik_seed_state.size());
913  error_code.val = error_code.NO_IK_SOLUTION;
914  return false;
915  }
916 
917  if (!consistency_limits.empty() && consistency_limits.size() != num_joints_)
918  {
919  ROS_ERROR_STREAM_NAMED("ikfast", "Consistency limits be empty or must have size "
920  << num_joints_ << " instead of size " << consistency_limits.size());
921  error_code.val = error_code.NO_IK_SOLUTION;
922  return false;
923  }
924 
925  // -------------------------------------------------------------------------------------------------
926  // Initialize
927 
928  KDL::Frame frame;
929  tf::poseMsgToKDL(ik_pose, frame);
930 
931  std::vector<double> vfree(free_params_.size());
932 
933  ros::Time maxTime = ros::Time::now() + ros::Duration(timeout);
934  int counter = 0;
935 
936  double initial_guess = ik_seed_state[free_params_[0]];
937  vfree[0] = initial_guess;
938 
939  // -------------------------------------------------------------------------------------------------
940  // Handle consitency limits if needed
941  int num_positive_increments;
942  int num_negative_increments;
943 
944  if (!consistency_limits.empty())
945  {
946  // moveit replaced consistency_limit (scalar) w/ consistency_limits (vector)
947  // Assume [0]th free_params element for now. Probably wrong.
948  double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess + consistency_limits[free_params_[0]]);
949  double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess - consistency_limits[free_params_[0]]);
950 
951  num_positive_increments = (int)((max_limit - initial_guess) / search_discretization_);
952  num_negative_increments = (int)((initial_guess - min_limit) / search_discretization_);
953  }
954  else // no consitency limits provided
955  {
956  num_positive_increments = (joint_max_vector_[free_params_[0]] - initial_guess) / search_discretization_;
957  num_negative_increments = (initial_guess - joint_min_vector_[free_params_[0]]) / search_discretization_;
958  }
959 
960  // -------------------------------------------------------------------------------------------------
961  // Begin searching
962 
963  ROS_DEBUG_STREAM_NAMED("ikfast", "Free param is " << free_params_[0] << " initial guess is " << initial_guess
964  << ", # positive increments: " << num_positive_increments
965  << ", # negative increments: " << num_negative_increments);
966  if ((search_mode & OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000)
967  ROS_WARN_STREAM_ONCE_NAMED("ikfast", "Large search space, consider increasing the search discretization");
968 
969  double best_costs = -1.0;
970  std::vector<double> best_solution;
971  int nattempts = 0, nvalid = 0;
972 
973  while (true)
974  {
975  IkSolutionList<IkReal> solutions;
976  int numsol = solve(frame, vfree, solutions);
977 
978  ROS_DEBUG_STREAM_NAMED("ikfast", "Found " << numsol << " solutions from IKFast");
979 
980  // ROS_INFO("%f",vfree[0]);
981 
982  if (numsol > 0)
983  {
984  for (int s = 0; s < numsol; ++s)
985  {
986  nattempts++;
987  std::vector<double> sol;
988  getSolution(solutions, ik_seed_state, s, sol);
989 
990  bool obeys_limits = true;
991  for (unsigned int i = 0; i < sol.size(); i++)
992  {
993  if (joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
994  {
995  obeys_limits = false;
996  break;
997  }
998  // ROS_INFO_STREAM_NAMED("ikfast","Num " << i << " value " << sol[i] << " has limits " <<
999  // joint_has_limits_vector_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i]);
1000  }
1001  if (obeys_limits)
1002  {
1003  getSolution(solutions, ik_seed_state, s, solution);
1004 
1005  // This solution is within joint limits, now check if in collision (if callback provided)
1006  if (!solution_callback.empty())
1007  {
1008  solution_callback(ik_pose, solution, error_code);
1009  }
1010  else
1011  {
1012  error_code.val = error_code.SUCCESS;
1013  }
1014 
1015  if (error_code.val == error_code.SUCCESS)
1016  {
1017  nvalid++;
1018  if (search_mode & OPTIMIZE_MAX_JOINT)
1019  {
1020  // Costs for solution: Largest joint motion
1021  double costs = 0.0;
1022  for (unsigned int i = 0; i < solution.size(); i++)
1023  {
1024  double d = fabs(ik_seed_state[i] - solution[i]);
1025  if (d > costs)
1026  costs = d;
1027  }
1028  if (costs < best_costs || best_costs == -1.0)
1029  {
1030  best_costs = costs;
1031  best_solution = solution;
1032  }
1033  }
1034  else
1035  // Return first feasible solution
1036  return true;
1037  }
1038  }
1039  }
1040  }
1041 
1042  if (!getCount(counter, num_positive_increments, -num_negative_increments))
1043  {
1044  // Everything searched
1045  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1046  break;
1047  }
1048 
1049  vfree[0] = initial_guess + search_discretization_ * counter;
1050  // ROS_DEBUG_STREAM_NAMED("ikfast","Attempt " << counter << " with 0th free joint having value " << vfree[0]);
1051  }
1052 
1053  ROS_DEBUG_STREAM_NAMED("ikfast", "Valid solutions: " << nvalid << "/" << nattempts);
1054 
1055  if ((search_mode & OPTIMIZE_MAX_JOINT) && best_costs != -1.0)
1056  {
1057  solution = best_solution;
1058  error_code.val = error_code.SUCCESS;
1059  return true;
1060  }
1061 
1062  // No solution found
1063  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1064  return false;
1065 }
1066 
1067 // Used when there are no redundant joints - aka no free params
1068 bool IKFastKinematicsPlugin::getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
1069  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
1070  const kinematics::KinematicsQueryOptions& options) const
1071 {
1072  ROS_DEBUG_STREAM_NAMED("ikfast", "getPositionIK");
1073 
1074  if (!active_)
1075  {
1076  ROS_ERROR("kinematics not active");
1077  return false;
1078  }
1079 
1080  if (ik_seed_state.size() < num_joints_)
1081  {
1082  ROS_ERROR_STREAM("ik_seed_state only has " << ik_seed_state.size() << " entries, this ikfast solver requires "
1083  << num_joints_);
1084  return false;
1085  }
1086 
1087  // Check if seed is in bound
1088  for (std::size_t i = 0; i < ik_seed_state.size(); i++)
1089  {
1090  // Add tolerance to limit check
1091  if (joint_has_limits_vector_[i] && ((ik_seed_state[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1092  (ik_seed_state[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1093  {
1094  ROS_DEBUG_STREAM_NAMED("ikseed", "Not in limits! " << (int)i << " value " << ik_seed_state[i]
1095  << " has limit: " << joint_has_limits_vector_[i] << " being "
1096  << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
1097  return false;
1098  }
1099  }
1100 
1101  std::vector<double> vfree(free_params_.size());
1102  for (std::size_t i = 0; i < free_params_.size(); ++i)
1103  {
1104  int p = free_params_[i];
1105  ROS_ERROR("%u is %f", p, ik_seed_state[p]); // DTC
1106  vfree[i] = ik_seed_state[p];
1107  }
1108 
1109  KDL::Frame frame;
1110  tf::poseMsgToKDL(ik_pose, frame);
1111 
1112  IkSolutionList<IkReal> solutions;
1113  int numsol = solve(frame, vfree, solutions);
1114  ROS_DEBUG_STREAM_NAMED("ikfast", "Found " << numsol << " solutions from IKFast");
1115 
1116  std::vector<LimitObeyingSol> solutions_obey_limits;
1117 
1118  if (numsol)
1119  {
1120  std::vector<double> solution_obey_limits;
1121  for (std::size_t s = 0; s < numsol; ++s)
1122  {
1123  std::vector<double> sol;
1124  getSolution(solutions, ik_seed_state, s, sol);
1125  ROS_DEBUG_NAMED("ikfast", "Sol %d: %e %e %e %e %e %e", (int)s, sol[0], sol[1], sol[2], sol[3], sol[4],
1126  sol[5]);
1127 
1128  bool obeys_limits = true;
1129  for (std::size_t i = 0; i < sol.size(); i++)
1130  {
1131  // Add tolerance to limit check
1132  if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1133  (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1134  {
1135  // One element of solution is not within limits
1136  obeys_limits = false;
1137  ROS_DEBUG_STREAM_NAMED("ikfast", "Not in limits! " << (int)i << " value " << sol[i] << " has limit: "
1138  << joint_has_limits_vector_[i] << " being "
1139  << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
1140  break;
1141  }
1142  }
1143  if (obeys_limits)
1144  {
1145  // All elements of this solution obey limits
1146  getSolution(solutions, ik_seed_state, s, solution_obey_limits);
1147  double dist_from_seed = 0.0;
1148  for (std::size_t i = 0; i < ik_seed_state.size(); ++i)
1149  {
1150  dist_from_seed += fabs(ik_seed_state[i] - solution_obey_limits[i]);
1151  }
1152 
1153  solutions_obey_limits.push_back({ solution_obey_limits, dist_from_seed });
1154  }
1155  }
1156  }
1157  else
1158  {
1159  ROS_DEBUG_STREAM_NAMED("ikfast", "No IK solution");
1160  }
1161 
1162  // Sort the solutions under limits and find the one that is closest to ik_seed_state
1163  if (!solutions_obey_limits.empty())
1164  {
1165  std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
1166  solution = solutions_obey_limits[0].value;
1167  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
1168  return true;
1169  }
1170 
1171  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1172  return false;
1173 }
1174 
1175 bool IKFastKinematicsPlugin::getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses,
1176  const std::vector<double>& ik_seed_state,
1177  std::vector<std::vector<double>>& solutions,
1179  const kinematics::KinematicsQueryOptions& options) const
1180 {
1181  ROS_DEBUG_STREAM_NAMED("ikfast", "getPositionIK with multiple solutions");
1182 
1183  if (!active_)
1184  {
1185  ROS_ERROR("kinematics not active");
1187  return false;
1188  }
1189 
1190  if (ik_poses.empty())
1191  {
1192  ROS_ERROR("ik_poses is empty");
1194  return false;
1195  }
1196 
1197  if (ik_poses.size() > 1)
1198  {
1199  ROS_ERROR("ik_poses contains multiple entries, only one is allowed");
1201  return false;
1202  }
1203 
1204  if (ik_seed_state.size() < num_joints_)
1205  {
1206  ROS_ERROR_STREAM("ik_seed_state only has " << ik_seed_state.size() << " entries, this ikfast solver requires "
1207  << num_joints_);
1208  return false;
1209  }
1210 
1211  KDL::Frame frame;
1212  tf::poseMsgToKDL(ik_poses[0], frame);
1213 
1214  // solving ik
1215  std::vector<IkSolutionList<IkReal>> solution_set;
1216  IkSolutionList<IkReal> ik_solutions;
1217  std::vector<double> vfree;
1218  int numsol = 0;
1219  std::vector<double> sampled_joint_vals;
1220  if (!redundant_joint_indices_.empty())
1221  {
1222  // initializing from seed
1223  sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]);
1224 
1225  // checking joint limits when using no discretization
1227  joint_has_limits_vector_[redundant_joint_indices_.front()])
1228  {
1229  double joint_min = joint_min_vector_[redundant_joint_indices_.front()];
1230  double joint_max = joint_max_vector_[redundant_joint_indices_.front()];
1231 
1232  double jv = sampled_joint_vals[0];
1233  if (!((jv > (joint_min - LIMIT_TOLERANCE)) && (jv < (joint_max + LIMIT_TOLERANCE))))
1234  {
1236  ROS_ERROR_STREAM("ik seed is out of bounds");
1237  return false;
1238  }
1239  }
1240 
1241  // computing all solutions sets for each sampled value of the redundant joint
1242  if (!sampleRedundantJoint(options.discretization_method, sampled_joint_vals))
1243  {
1245  return false;
1246  }
1247 
1248  for (unsigned int i = 0; i < sampled_joint_vals.size(); i++)
1249  {
1250  vfree.clear();
1251  vfree.push_back(sampled_joint_vals[i]);
1252  numsol += solve(frame, vfree, ik_solutions);
1253  solution_set.push_back(ik_solutions);
1254  }
1255  }
1256  else
1257  {
1258  // computing for single solution set
1259  numsol = solve(frame, vfree, ik_solutions);
1260  solution_set.push_back(ik_solutions);
1261  }
1262 
1263  ROS_DEBUG_STREAM_NAMED("ikfast", "Found " << numsol << " solutions from IKFast");
1264  bool solutions_found = false;
1265  if (numsol > 0)
1266  {
1267  /*
1268  Iterating through all solution sets and storing those that do not exceed joint limits.
1269  */
1270  for (unsigned int r = 0; r < solution_set.size(); r++)
1271  {
1272  ik_solutions = solution_set[r];
1273  numsol = ik_solutions.GetNumSolutions();
1274  for (int s = 0; s < numsol; ++s)
1275  {
1276  std::vector<double> sol;
1277  getSolution(ik_solutions, ik_seed_state, s, sol);
1278 
1279  bool obeys_limits = true;
1280  for (unsigned int i = 0; i < sol.size(); i++)
1281  {
1282  // Add tolerance to limit check
1283  if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1284  (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1285  {
1286  // One element of solution is not within limits
1287  obeys_limits = false;
1289  "ikfast", "Not in limits! " << i << " value " << sol[i] << " has limit: " << joint_has_limits_vector_[i]
1290  << " being " << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
1291  break;
1292  }
1293  }
1294  if (obeys_limits)
1295  {
1296  // All elements of solution obey limits
1297  solutions_found = true;
1298  solutions.push_back(sol);
1299  }
1300  }
1301  }
1302 
1303  if (solutions_found)
1304  {
1306  return true;
1307  }
1308  }
1309  else
1310  {
1311  ROS_DEBUG_STREAM_NAMED("ikfast", "No IK solution");
1312  }
1313 
1315  return false;
1316 }
1317 
1319  std::vector<double>& sampled_joint_vals) const
1320 {
1321  double joint_min = -M_PI;
1322  double joint_max = M_PI;
1323  int index = redundant_joint_indices_.front();
1324  double joint_dscrt = redundant_joint_discretization_.at(index);
1325 
1326  if (joint_has_limits_vector_[redundant_joint_indices_.front()])
1327  {
1328  joint_min = joint_min_vector_[index];
1329  joint_max = joint_max_vector_[index];
1330  }
1331 
1332  switch (method)
1333  {
1335  {
1336  int steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1337  for (unsigned int i = 0; i < steps; i++)
1338  {
1339  sampled_joint_vals.push_back(joint_min + joint_dscrt * i);
1340  }
1341  sampled_joint_vals.push_back(joint_max);
1342  }
1343  break;
1345  {
1346  int steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1347  steps = steps > 0 ? steps : 1;
1348  double diff = joint_max - joint_min;
1349  for (int i = 0; i < steps; i++)
1350  {
1351  sampled_joint_vals.push_back(((diff * std::rand()) / (static_cast<double>(RAND_MAX))) + joint_min);
1352  }
1353  }
1354 
1355  break;
1357 
1358  break;
1359  default:
1360  ROS_ERROR_STREAM("Discretization method " << method << " is not supported");
1361  return false;
1362  }
1363 
1364  return true;
1365 }
1366 
1367 } // end namespace
d
virtual const IkSolutionBase< T > & GetSolution(size_t index) const
returns the solution pointer
Definition: ikfast.h:283
KinematicError kinematic_error
#define ROS_FATAL(...)
void getClosestSolution(const IkSolutionList< IkReal > &solutions, const std::vector< double > &ik_seed_state, std::vector< double > &solution) const
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
URDF_EXPORT bool initString(const std::string &xmlstring)
#define ROS_WARN_NAMED(name,...)
ROSCONSOLE_DECL void initialize()
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
Given a set of joint angles and a set of links, compute their pose.
void getSolution(const IkSolutionList< IkReal > &solutions, int i, std::vector< double > &solution) const
Gets a specific solution from the set.
virtual size_t GetNumSolutions() const
returns the number of solutions stored
Definition: ikfast.h:294
XmlRpcServer s
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
The discrete solutions are returned in this structure.
Definition: ikfast.h:70
#define ROS_INFO_STREAM_NAMED(name, args)
#define M_PI
virtual void Clear()
clears all current solutions, note that any memory addresses returned from GetSolution will be invali...
Definition: ikfast.h:299
virtual const std::vector< int > & GetFree() const =0
Gets the indices of the configuration space that have to be preset before a full solution can be retu...
IKFAST_API bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
IkParameterizationType
The types of inverse kinematics parameterizations supported.
Rotation M
ray on end effector coordinate system reaches desired global ray
direction on end effector coordinate system points to desired 3D position
#define ROS_DEBUG_NAMED(name,...)
SEARCH_MODE
Search modes for searchPositionIK(), see there.
unsigned int index
double harmonize(const std::vector< double > &ik_seed_state, std::vector< double > &solution) const
#define ROS_WARN_STREAM_ONCE_NAMED(name, args)
#define ROS_FATAL_STREAM_NAMED(name, args)
bool searchParam(const std::string &key, std::string &result) const
double data[3]
bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices)
Overrides the default method to prevent changing the redundant joints.
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
DiscretizationMethod discretization_method
void setSearchDiscretization(const std::map< int, double > &discretization)
Sets the discretization value for the redundant joint.
def xml_string(rootXml, addHeader=True)
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
Given a desired pose of the end-effector, search for the joint angles required to reach it...
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
direction on end effector coordinate system reaches desired direction
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
Given a desired pose of the end-effector, compute the joint angles to reach it.
virtual void GetSolution(T *solution, const T *freevalues) const =0
gets a concrete solution
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
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)
Default implementation of IkSolutionListBase.
Definition: ikfast.h:273
bool getParam(const std::string &key, std::string &s) const
#define ROS_FATAL_NAMED(name,...)
IKFAST_API void ComputeFk(const IkReal *j, IkReal *eetrans, IkReal *eerot)
bool sampleRedundantJoint(kinematics::DiscretizationMethod method, std::vector< double > &sampled_joint_vals) const
samples the designated redundant joint using the chosen discretization method
#define ROS_ERROR_NAMED(name,...)
int solve(KDL::Frame &pose_frame, const std::vector< double > &vfree, IkSolutionList< IkReal > &solutions) const
Calls the IK solver from IKFast.
static Time now()
#define ROS_ERROR_STREAM(args)
r
#define ROS_ERROR(...)
bit is set if the data represents the time-derivate velocity of an IkParameterization ...
#define ROS_WARN_STREAM_NAMED(name, args)
double data[9]


kr6_r900_workspace_ikfast_manipulator_plugin
Author(s):
autogenerated on Thu Jul 18 2019 04:03:29