duaro_upper_arm_ikfast_moveit_plugin.cpp
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,
81  IKP_TranslationDirection5D = 0x56000007,
82  IKP_TranslationXY2D = 0x22000008,
85  IKP_TranslationXYOrientation3D = 0x33000009,
86  IKP_TranslationLocalGlobal6D = 0x3600000a,
89 
90  IKP_TranslationXAxisAngle4D = 0x4400000b,
91  IKP_TranslationYAxisAngle4D = 0x4400000c,
94  IKP_TranslationZAxisAngle4D = 0x4400000d,
97 
100  IKP_TranslationXAxisAngleZNorm4D = 0x4400000e,
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
140 struct LimitObeyingSol
141 {
142  std::vector<double> value;
143  double dist_from_seed;
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  std::vector<std::string> joint_names_;
157  std::vector<double> joint_min_vector_;
158  std::vector<double> joint_max_vector_;
159  std::vector<bool> joint_has_limits_vector_;
160  std::vector<std::string> link_names_;
161  const size_t num_joints_;
162  std::vector<int> free_params_;
163  bool active_; // Internal variable that indicates whether solvers are configured and ready
164  const std::string name_{ "ikfast" };
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  }
174 
175 public:
179  IKFastKinematicsPlugin() : num_joints_(GetNumJoints()), 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,
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 private:
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 
353  if (free_params_.size() > 1)
354  {
355  ROS_FATAL("Only one free joint parameter supported!");
356  return false;
357  }
358  else if (free_params_.size() == 1)
359  {
360  redundant_joint_indices_.clear();
361  redundant_joint_indices_.push_back(free_params_[0]);
362  KinematicsBase::setSearchDiscretization(DEFAULT_SEARCH_DISCRETIZATION);
363  }
364 
365  urdf::Model robot_model;
366  std::string xml_string;
367 
368  std::string urdf_xml, full_urdf_xml;
369  lookupParam("urdf_xml", urdf_xml, robot_description);
370  node_handle.searchParam(urdf_xml, full_urdf_xml);
371 
372  ROS_DEBUG_NAMED(name_, "Reading xml file from parameter server");
373  if (!node_handle.getParam(full_urdf_xml, xml_string))
374  {
375  ROS_FATAL_NAMED(name_, "Could not load the xml from parameter server: %s", urdf_xml.c_str());
376  return false;
377  }
378 
379  robot_model.initString(xml_string);
380 
381  ROS_DEBUG_STREAM_NAMED(name_, "Reading joints and links from URDF");
382 
383  urdf::LinkConstSharedPtr link = robot_model.getLink(getTipFrame());
384  while (link->name != base_frame_ && joint_names_.size() <= num_joints_)
385  {
386  ROS_DEBUG_NAMED(name_, "Link %s", link->name.c_str());
387  link_names_.push_back(link->name);
388  urdf::JointSharedPtr joint = link->parent_joint;
389  if (joint)
390  {
391  if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
392  {
393  ROS_DEBUG_STREAM_NAMED(name_, "Adding joint " << joint->name);
394 
395  joint_names_.push_back(joint->name);
396  float lower, upper;
397  int hasLimits;
398  if (joint->type != urdf::Joint::CONTINUOUS)
399  {
400  if (joint->safety)
401  {
402  lower = joint->safety->soft_lower_limit;
403  upper = joint->safety->soft_upper_limit;
404  }
405  else
406  {
407  lower = joint->limits->lower;
408  upper = joint->limits->upper;
409  }
410  hasLimits = 1;
411  }
412  else
413  {
414  lower = -M_PI;
415  upper = M_PI;
416  hasLimits = 0;
417  }
418  if (hasLimits)
419  {
420  joint_has_limits_vector_.push_back(true);
421  joint_min_vector_.push_back(lower);
422  joint_max_vector_.push_back(upper);
423  }
424  else
425  {
426  joint_has_limits_vector_.push_back(false);
427  joint_min_vector_.push_back(-M_PI);
428  joint_max_vector_.push_back(M_PI);
429  }
430  }
431  }
432  else
433  {
434  ROS_WARN_NAMED(name_, "no joint corresponding to %s", link->name.c_str());
435  }
436  link = link->getParent();
437  }
438 
439  if (joint_names_.size() != num_joints_)
440  {
441  ROS_FATAL_STREAM_NAMED(name_, "Joint numbers mismatch: URDF has " << joint_names_.size() << " and IKFast has "
442  << num_joints_);
443  return false;
444  }
445 
446  std::reverse(link_names_.begin(), link_names_.end());
447  std::reverse(joint_names_.begin(), joint_names_.end());
448  std::reverse(joint_min_vector_.begin(), joint_min_vector_.end());
449  std::reverse(joint_max_vector_.begin(), joint_max_vector_.end());
450  std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end());
451 
452  for (size_t i = 0; i < num_joints_; ++i)
453  ROS_DEBUG_STREAM_NAMED(name_, joint_names_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i] << " "
454  << joint_has_limits_vector_[i]);
455 
456  active_ = true;
457  return true;
458 }
459 
460 void IKFastKinematicsPlugin::setSearchDiscretization(const std::map<int, double>& discretization)
461 {
462  if (discretization.empty())
463  {
464  ROS_ERROR("The 'discretization' map is empty");
465  return;
466  }
467 
468  if (redundant_joint_indices_.empty())
469  {
470  ROS_ERROR_STREAM("This group's solver doesn't support redundant joints");
471  return;
472  }
473 
474  if (discretization.begin()->first != redundant_joint_indices_[0])
475  {
476  std::string redundant_joint = joint_names_[free_params_[0]];
477  ROS_ERROR_STREAM("Attempted to discretize a non-redundant joint "
478  << discretization.begin()->first << ", only joint '" << redundant_joint << "' with index "
479  << redundant_joint_indices_[0] << " is redundant.");
480  return;
481  }
482 
483  if (discretization.begin()->second <= 0.0)
484  {
485  ROS_ERROR_STREAM("Discretization can not takes values that are <= 0");
486  return;
487  }
488 
489  redundant_joint_discretization_.clear();
490  redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second;
491 }
492 
493 bool IKFastKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices)
494 {
495  ROS_ERROR_STREAM("Changing the redundant joints isn't permitted by this group's solver ");
496  return false;
497 }
498 
499 int IKFastKinematicsPlugin::solve(KDL::Frame& pose_frame, const std::vector<double>& vfree,
500  IkSolutionList<IkReal>& solutions) const
501 {
502  // IKFast56/61
503  solutions.Clear();
504 
505  double trans[3];
506  trans[0] = pose_frame.p[0]; //-.18;
507  trans[1] = pose_frame.p[1];
508  trans[2] = pose_frame.p[2];
509 
510  KDL::Rotation mult;
511  KDL::Vector direction;
512 
513  switch (GetIkType())
514  {
515  case IKP_Transform6D:
516  case IKP_Translation3D:
517  // For **Transform6D**, eerot is 9 values for the 3x3 rotation matrix. For **Translation3D**, these are ignored.
518 
519  mult = pose_frame.M;
520 
521  double vals[9];
522  vals[0] = mult(0, 0);
523  vals[1] = mult(0, 1);
524  vals[2] = mult(0, 2);
525  vals[3] = mult(1, 0);
526  vals[4] = mult(1, 1);
527  vals[5] = mult(1, 2);
528  vals[6] = mult(2, 0);
529  vals[7] = mult(2, 1);
530  vals[8] = mult(2, 2);
531 
532  // IKFast56/61
533  ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
534  return solutions.GetNumSolutions();
535 
536  case IKP_Direction3D:
537  case IKP_Ray4D:
539  // For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target
540  // direction.
541 
542  direction = pose_frame.M * KDL::Vector(0, 0, 1);
543  ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
544  return solutions.GetNumSolutions();
545 
549  // For **TranslationXAxisAngle4D**, **TranslationYAxisAngle4D**, and **TranslationZAxisAngle4D**, the first value
550  // represents the angle.
551  ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet.");
552  return 0;
553 
555  // For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end
556  // effector coordinate system.
557  ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet.");
558  return 0;
559 
560  case IKP_Rotation3D:
561  case IKP_Lookat3D:
562  case IKP_TranslationXY2D:
564  ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet.");
565  return 0;
566 
568  double roll, pitch, yaw;
569  // For **TranslationXAxisAngleZNorm4D** - end effector origin reaches desired 3D translation, manipulator
570  // direction needs to be orthogonal to z axis and be rotated at a certain angle starting from the x axis (defined
571  // in the manipulator base link’s coordinate system)
572  pose_frame.M.GetRPY(roll, pitch, yaw);
573  ComputeIk(trans, &yaw, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
574  return solutions.GetNumSolutions();
575 
577  // For **TranslationYAxisAngleXNorm4D** - end effector origin reaches desired 3D translation, manipulator
578  // direction needs to be orthogonal to x axis and be rotated at a certain angle starting from the y axis (defined
579  // in the manipulator base link’s coordinate system)
580  pose_frame.M.GetRPY(roll, pitch, yaw);
581  ComputeIk(trans, &roll, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
582  return solutions.GetNumSolutions();
583 
585  // For **TranslationZAxisAngleYNorm4D** - end effector origin reaches desired 3D translation, manipulator
586  // direction needs to be orthogonal to y axis and be rotated at a certain angle starting from the z axis (defined
587  // in the manipulator base link’s coordinate system)
588  pose_frame.M.GetRPY(roll, pitch, yaw);
589  ComputeIk(trans, &pitch, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
590  return solutions.GetNumSolutions();
591 
592  default:
593  ROS_ERROR_NAMED(name_, "Unknown IkParameterizationType! Was the solver generated with an incompatible version "
594  "of Openrave?");
595  return 0;
596  }
597 }
598 
600  std::vector<double>& solution) const
601 {
602  solution.clear();
603  solution.resize(num_joints_);
604 
605  // IKFast56/61
606  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
607  std::vector<IkReal> vsolfree(sol.GetFree().size());
608  sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : NULL);
609 
610  // std::cout << "solution " << i << ":" ;
611  // for(int j=0;j<num_joints_; ++j)
612  // std::cout << " " << solution[j];
613  // std::cout << std::endl;
614 
615  // ROS_ERROR("%f %d",solution[2],vsolfree.size());
616 }
617 
619  const std::vector<double>& ik_seed_state, int i,
620  std::vector<double>& solution) const
621 {
622  solution.clear();
623  solution.resize(num_joints_);
624 
625  // IKFast56/61
626  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
627  std::vector<IkReal> vsolfree(sol.GetFree().size());
628  sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : NULL);
629 
630  // rotate joints by +/-360° where it is possible and useful
631  for (std::size_t i = 0; i < num_joints_; ++i)
632  {
633  if (joint_has_limits_vector_[i])
634  {
635  double signed_distance = solution[i] - ik_seed_state[i];
636  while (signed_distance > M_PI && solution[i] - 2 * M_PI > (joint_min_vector_[i] - LIMIT_TOLERANCE))
637  {
638  signed_distance -= 2 * M_PI;
639  solution[i] -= 2 * M_PI;
640  }
641  while (signed_distance < -M_PI && solution[i] + 2 * M_PI < (joint_max_vector_[i] + LIMIT_TOLERANCE))
642  {
643  signed_distance += 2 * M_PI;
644  solution[i] += 2 * M_PI;
645  }
646  }
647  }
648 }
649 
650 double IKFastKinematicsPlugin::harmonize(const std::vector<double>& ik_seed_state, std::vector<double>& solution) const
651 {
652  double dist_sqr = 0;
653  std::vector<double> ss = ik_seed_state;
654  for (size_t i = 0; i < ik_seed_state.size(); ++i)
655  {
656  while (ss[i] > 2 * M_PI)
657  {
658  ss[i] -= 2 * M_PI;
659  }
660  while (ss[i] < 2 * M_PI)
661  {
662  ss[i] += 2 * M_PI;
663  }
664  while (solution[i] > 2 * M_PI)
665  {
666  solution[i] -= 2 * M_PI;
667  }
668  while (solution[i] < 2 * M_PI)
669  {
670  solution[i] += 2 * M_PI;
671  }
672  dist_sqr += fabs(ik_seed_state[i] - solution[i]);
673  }
674  return dist_sqr;
675 }
676 
677 // void IKFastKinematicsPlugin::getOrderedSolutions(const std::vector<double> &ik_seed_state,
678 // std::vector<std::vector<double> >& solslist)
679 // {
680 // std::vector<double>
681 // double mindist = 0;
682 // int minindex = -1;
683 // std::vector<double> sol;
684 // for(size_t i=0;i<solslist.size();++i){
685 // getSolution(i,sol);
686 // double dist = harmonize(ik_seed_state, sol);
687 // //std::cout << "dist[" << i << "]= " << dist << std::endl;
688 // if(minindex == -1 || dist<mindist){
689 // minindex = i;
690 // mindist = dist;
691 // }
692 // }
693 // if(minindex >= 0){
694 // getSolution(minindex,solution);
695 // harmonize(ik_seed_state, solution);
696 // index = minindex;
697 // }
698 // }
699 
701  const std::vector<double>& ik_seed_state,
702  std::vector<double>& solution) const
703 {
704  double mindist = DBL_MAX;
705  int minindex = -1;
706  std::vector<double> sol;
707 
708  // IKFast56/61
709  for (size_t i = 0; i < solutions.GetNumSolutions(); ++i)
710  {
711  getSolution(solutions, i, sol);
712  double dist = harmonize(ik_seed_state, sol);
713  ROS_INFO_STREAM_NAMED(name_, "Dist " << i << " dist " << dist);
714  // std::cout << "dist[" << i << "]= " << dist << std::endl;
715  if (minindex == -1 || dist < mindist)
716  {
717  minindex = i;
718  mindist = dist;
719  }
720  }
721  if (minindex >= 0)
722  {
723  getSolution(solutions, minindex, solution);
724  harmonize(ik_seed_state, solution);
725  }
726 }
727 
728 void IKFastKinematicsPlugin::fillFreeParams(int count, int* array)
729 {
730  free_params_.clear();
731  for (int i = 0; i < count; ++i)
732  free_params_.push_back(array[i]);
733 }
734 
735 bool IKFastKinematicsPlugin::getCount(int& count, const int& max_count, const int& min_count) const
736 {
737  if (count > 0)
738  {
739  if (-count >= min_count)
740  {
741  count = -count;
742  return true;
743  }
744  else if (count + 1 <= max_count)
745  {
746  count = count + 1;
747  return true;
748  }
749  else
750  {
751  return false;
752  }
753  }
754  else
755  {
756  if (1 - count <= max_count)
757  {
758  count = 1 - count;
759  return true;
760  }
761  else if (count - 1 >= min_count)
762  {
763  count = count - 1;
764  return true;
765  }
766  else
767  return false;
768  }
769 }
770 
771 bool IKFastKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
772  const std::vector<double>& joint_angles,
773  std::vector<geometry_msgs::Pose>& poses) const
774 {
775  if (GetIkType() != IKP_Transform6D)
776  {
777  // ComputeFk() is the inverse function of ComputeIk(), so the format of
778  // eerot differs depending on IK type. The Transform6D IK type is the only
779  // one for which a 3x3 rotation matrix is returned, which means we can only
780  // compute FK for that IK type.
781  ROS_ERROR_NAMED(name_, "Can only compute FK for Transform6D IK type!");
782  return false;
783  }
784 
785  KDL::Frame p_out;
786  if (link_names.size() == 0)
787  {
788  ROS_WARN_STREAM_NAMED(name_, "Link names with nothing");
789  return false;
790  }
791 
792  if (link_names.size() != 1 || link_names[0] != getTipFrame())
793  {
794  ROS_ERROR_NAMED(name_, "Can compute FK for %s only", getTipFrame().c_str());
795  return false;
796  }
797 
798  bool valid = true;
799 
800  IkReal eerot[9], eetrans[3];
801 
802  if (joint_angles.size() != num_joints_)
803  {
804  ROS_ERROR_NAMED(name_, "Unexpected number of joint angles");
805  return false;
806  }
807 
808  IkReal angles[num_joints_];
809  for (unsigned char i = 0; i < num_joints_; i++)
810  angles[i] = joint_angles[i];
811 
812  // IKFast56/61
813  ComputeFk(angles, eetrans, eerot);
814 
815  for (int i = 0; i < 3; ++i)
816  p_out.p.data[i] = eetrans[i];
817 
818  for (int i = 0; i < 9; ++i)
819  p_out.M.data[i] = eerot[i];
820 
821  poses.resize(1);
822  tf::poseKDLToMsg(p_out, poses[0]);
823 
824  return valid;
825 }
826 
827 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
828  const std::vector<double>& ik_seed_state, double timeout,
829  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
830  const kinematics::KinematicsQueryOptions& options) const
831 {
832  const IKCallbackFn solution_callback = 0;
833  std::vector<double> consistency_limits;
834 
835  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
836  options);
837 }
838 
839 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
840  const std::vector<double>& ik_seed_state, double timeout,
841  const std::vector<double>& consistency_limits,
842  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
843  const kinematics::KinematicsQueryOptions& options) const
844 {
845  const IKCallbackFn solution_callback = 0;
846  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
847  options);
848 }
849 
850 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
851  const std::vector<double>& ik_seed_state, double timeout,
852  std::vector<double>& solution, const IKCallbackFn& solution_callback,
853  moveit_msgs::MoveItErrorCodes& error_code,
854  const kinematics::KinematicsQueryOptions& options) const
855 {
856  std::vector<double> consistency_limits;
857  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
858  options);
859 }
860 
861 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
862  const std::vector<double>& ik_seed_state, double timeout,
863  const std::vector<double>& consistency_limits,
864  std::vector<double>& solution, const IKCallbackFn& solution_callback,
865  moveit_msgs::MoveItErrorCodes& error_code,
866  const kinematics::KinematicsQueryOptions& options) const
867 {
868  ROS_DEBUG_STREAM_NAMED(name_, "searchPositionIK");
869 
871  SEARCH_MODE search_mode = OPTIMIZE_MAX_JOINT;
872 
873  // Check if there are no redundant joints
874  if (free_params_.size() == 0)
875  {
876  ROS_DEBUG_STREAM_NAMED(name_, "No need to search since no free params/redundant joints");
877 
878  std::vector<geometry_msgs::Pose> ik_poses(1, ik_pose);
879  std::vector<std::vector<double>> solutions;
880  kinematics::KinematicsResult kinematic_result;
881  // Find all IK solution within joint limits
882  if (!getPositionIK(ik_poses, ik_seed_state, solutions, kinematic_result, options))
883  {
884  ROS_DEBUG_STREAM_NAMED(name_, "No solution whatsoever");
885  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
886  return false;
887  }
888 
889  // sort solutions by their distance to the seed
890  std::vector<LimitObeyingSol> solutions_obey_limits;
891  for (std::size_t i = 0; i < solutions.size(); ++i)
892  {
893  double dist_from_seed = 0.0;
894  for (std::size_t j = 0; j < ik_seed_state.size(); ++j)
895  {
896  dist_from_seed += fabs(ik_seed_state[j] - solutions[i][j]);
897  }
898 
899  solutions_obey_limits.push_back({ solutions[i], dist_from_seed });
900  }
901  std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
902 
903  // check for collisions if a callback is provided
904  if (!solution_callback.empty())
905  {
906  for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i)
907  {
908  solution_callback(ik_pose, solutions_obey_limits[i].value, error_code);
909  if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
910  {
911  solution = solutions_obey_limits[i].value;
912  ROS_DEBUG_STREAM_NAMED(name_, "Solution passes callback");
913  return true;
914  }
915  }
916 
917  ROS_DEBUG_STREAM_NAMED(name_, "Solution has error code " << error_code);
918  return false;
919  }
920  else
921  {
922  solution = solutions_obey_limits[0].value;
923  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
924  return true; // no collision check callback provided
925  }
926  }
927 
928  // -------------------------------------------------------------------------------------------------
929  // Error Checking
930  if (!active_)
931  {
932  ROS_ERROR_STREAM_NAMED(name_, "Kinematics not active");
933  error_code.val = error_code.NO_IK_SOLUTION;
934  return false;
935  }
936 
937  if (ik_seed_state.size() != num_joints_)
938  {
939  ROS_ERROR_STREAM_NAMED(name_, "Seed state must have size " << num_joints_ << " instead of size "
940  << ik_seed_state.size());
941  error_code.val = error_code.NO_IK_SOLUTION;
942  return false;
943  }
944 
945  if (!consistency_limits.empty() && consistency_limits.size() != num_joints_)
946  {
947  ROS_ERROR_STREAM_NAMED(name_, "Consistency limits be empty or must have size " << num_joints_ << " instead of size "
948  << consistency_limits.size());
949  error_code.val = error_code.NO_IK_SOLUTION;
950  return false;
951  }
952 
953  // -------------------------------------------------------------------------------------------------
954  // Initialize
955 
956  KDL::Frame frame;
957  tf::poseMsgToKDL(ik_pose, frame);
958 
959  std::vector<double> vfree(free_params_.size());
960 
961  ros::Time maxTime = ros::Time::now() + ros::Duration(timeout);
962  int counter = 0;
963 
964  double initial_guess = ik_seed_state[free_params_[0]];
965  vfree[0] = initial_guess;
966 
967  // -------------------------------------------------------------------------------------------------
968  // Handle consitency limits if needed
969  int num_positive_increments;
970  int num_negative_increments;
971 
972  if (!consistency_limits.empty())
973  {
974  // moveit replaced consistency_limit (scalar) w/ consistency_limits (vector)
975  // Assume [0]th free_params element for now. Probably wrong.
976  double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess + consistency_limits[free_params_[0]]);
977  double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess - consistency_limits[free_params_[0]]);
978 
979  num_positive_increments = (int)((max_limit - initial_guess) / search_discretization_);
980  num_negative_increments = (int)((initial_guess - min_limit) / search_discretization_);
981  }
982  else // no consitency limits provided
983  {
984  num_positive_increments = (joint_max_vector_[free_params_[0]] - initial_guess) / search_discretization_;
985  num_negative_increments = (initial_guess - joint_min_vector_[free_params_[0]]) / search_discretization_;
986  }
987 
988  // -------------------------------------------------------------------------------------------------
989  // Begin searching
990 
991  ROS_DEBUG_STREAM_NAMED(name_, "Free param is " << free_params_[0] << " initial guess is " << initial_guess
992  << ", # positive increments: " << num_positive_increments
993  << ", # negative increments: " << num_negative_increments);
994  if ((search_mode & OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000)
995  ROS_WARN_STREAM_ONCE_NAMED(name_, "Large search space, consider increasing the search discretization");
996 
997  double best_costs = -1.0;
998  std::vector<double> best_solution;
999  int nattempts = 0, nvalid = 0;
1000 
1001  while (true)
1002  {
1003  IkSolutionList<IkReal> solutions;
1004  int numsol = solve(frame, vfree, solutions);
1005 
1006  ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast");
1007 
1008  // ROS_INFO("%f",vfree[0]);
1009 
1010  if (numsol > 0)
1011  {
1012  for (int s = 0; s < numsol; ++s)
1013  {
1014  nattempts++;
1015  std::vector<double> sol;
1016  getSolution(solutions, ik_seed_state, s, sol);
1017 
1018  bool obeys_limits = true;
1019  for (unsigned int i = 0; i < sol.size(); i++)
1020  {
1021  if (joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
1022  {
1023  obeys_limits = false;
1024  break;
1025  }
1026  // ROS_INFO_STREAM_NAMED(name_,"Num " << i << " value " << sol[i] << " has limits " <<
1027  // joint_has_limits_vector_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i]);
1028  }
1029  if (obeys_limits)
1030  {
1031  getSolution(solutions, ik_seed_state, s, solution);
1032 
1033  // This solution is within joint limits, now check if in collision (if callback provided)
1034  if (!solution_callback.empty())
1035  {
1036  solution_callback(ik_pose, solution, error_code);
1037  }
1038  else
1039  {
1040  error_code.val = error_code.SUCCESS;
1041  }
1042 
1043  if (error_code.val == error_code.SUCCESS)
1044  {
1045  nvalid++;
1046  if (search_mode & OPTIMIZE_MAX_JOINT)
1047  {
1048  // Costs for solution: Largest joint motion
1049  double costs = 0.0;
1050  for (unsigned int i = 0; i < solution.size(); i++)
1051  {
1052  double d = fabs(ik_seed_state[i] - solution[i]);
1053  if (d > costs)
1054  costs = d;
1055  }
1056  if (costs < best_costs || best_costs == -1.0)
1057  {
1058  best_costs = costs;
1059  best_solution = solution;
1060  }
1061  }
1062  else
1063  // Return first feasible solution
1064  return true;
1065  }
1066  }
1067  }
1068  }
1069 
1070  if (!getCount(counter, num_positive_increments, -num_negative_increments))
1071  {
1072  // Everything searched
1073  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1074  break;
1075  }
1076 
1077  vfree[0] = initial_guess + search_discretization_ * counter;
1078  // ROS_DEBUG_STREAM_NAMED(name_,"Attempt " << counter << " with 0th free joint having value " << vfree[0]);
1079  }
1080 
1081  ROS_DEBUG_STREAM_NAMED(name_, "Valid solutions: " << nvalid << "/" << nattempts);
1082 
1083  if ((search_mode & OPTIMIZE_MAX_JOINT) && best_costs != -1.0)
1084  {
1085  solution = best_solution;
1086  error_code.val = error_code.SUCCESS;
1087  return true;
1088  }
1089 
1090  // No solution found
1091  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1092  return false;
1093 }
1094 
1095 // Used when there are no redundant joints - aka no free params
1096 bool IKFastKinematicsPlugin::getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
1097  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
1098  const kinematics::KinematicsQueryOptions& options) const
1099 {
1100  ROS_DEBUG_STREAM_NAMED(name_, "getPositionIK");
1101 
1102  if (!active_)
1103  {
1104  ROS_ERROR("kinematics not active");
1105  return false;
1106  }
1107 
1108  if (ik_seed_state.size() < num_joints_)
1109  {
1110  ROS_ERROR_STREAM("ik_seed_state only has " << ik_seed_state.size() << " entries, this ikfast solver requires "
1111  << num_joints_);
1112  return false;
1113  }
1114 
1115  // Check if seed is in bound
1116  for (std::size_t i = 0; i < ik_seed_state.size(); i++)
1117  {
1118  // Add tolerance to limit check
1119  if (joint_has_limits_vector_[i] && ((ik_seed_state[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1120  (ik_seed_state[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1121  {
1122  ROS_DEBUG_STREAM_NAMED("ikseed", "Not in limits! " << (int)i << " value " << ik_seed_state[i]
1123  << " has limit: " << joint_has_limits_vector_[i] << " being "
1124  << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
1125  return false;
1126  }
1127  }
1128 
1129  std::vector<double> vfree(free_params_.size());
1130  for (std::size_t i = 0; i < free_params_.size(); ++i)
1131  {
1132  int p = free_params_[i];
1133  ROS_ERROR("%u is %f", p, ik_seed_state[p]); // DTC
1134  vfree[i] = ik_seed_state[p];
1135  }
1136 
1137  KDL::Frame frame;
1138  tf::poseMsgToKDL(ik_pose, frame);
1139 
1140  IkSolutionList<IkReal> solutions;
1141  int numsol = solve(frame, vfree, solutions);
1142  ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast");
1143 
1144  std::vector<LimitObeyingSol> solutions_obey_limits;
1145 
1146  if (numsol)
1147  {
1148  std::vector<double> solution_obey_limits;
1149  for (std::size_t s = 0; s < numsol; ++s)
1150  {
1151  std::vector<double> sol;
1152  getSolution(solutions, ik_seed_state, s, sol);
1153  ROS_DEBUG_NAMED(name_, "Sol %d: %e %e %e %e %e %e", (int)s, sol[0], sol[1], sol[2], sol[3], sol[4],
1154  sol[5]);
1155 
1156  bool obeys_limits = true;
1157  for (std::size_t i = 0; i < sol.size(); i++)
1158  {
1159  // Add tolerance to limit check
1160  if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1161  (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1162  {
1163  // One element of solution is not within limits
1164  obeys_limits = false;
1165  ROS_DEBUG_STREAM_NAMED(name_, "Not in limits! " << (int)i << " value " << sol[i] << " has limit: "
1166  << joint_has_limits_vector_[i] << " being "
1167  << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
1168  break;
1169  }
1170  }
1171  if (obeys_limits)
1172  {
1173  // All elements of this solution obey limits
1174  getSolution(solutions, ik_seed_state, s, solution_obey_limits);
1175  double dist_from_seed = 0.0;
1176  for (std::size_t i = 0; i < ik_seed_state.size(); ++i)
1177  {
1178  dist_from_seed += fabs(ik_seed_state[i] - solution_obey_limits[i]);
1179  }
1180 
1181  solutions_obey_limits.push_back({ solution_obey_limits, dist_from_seed });
1182  }
1183  }
1184  }
1185  else
1186  {
1187  ROS_DEBUG_STREAM_NAMED(name_, "No IK solution");
1188  }
1189 
1190  // Sort the solutions under limits and find the one that is closest to ik_seed_state
1191  if (!solutions_obey_limits.empty())
1192  {
1193  std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
1194  solution = solutions_obey_limits[0].value;
1195  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
1196  return true;
1197  }
1198 
1199  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1200  return false;
1201 }
1202 
1203 bool IKFastKinematicsPlugin::getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses,
1204  const std::vector<double>& ik_seed_state,
1205  std::vector<std::vector<double>>& solutions,
1207  const kinematics::KinematicsQueryOptions& options) const
1208 {
1209  ROS_DEBUG_STREAM_NAMED(name_, "getPositionIK with multiple solutions");
1210 
1211  if (!active_)
1212  {
1213  ROS_ERROR("kinematics not active");
1215  return false;
1216  }
1217 
1218  if (ik_poses.empty())
1219  {
1220  ROS_ERROR("ik_poses is empty");
1222  return false;
1223  }
1224 
1225  if (ik_poses.size() > 1)
1226  {
1227  ROS_ERROR("ik_poses contains multiple entries, only one is allowed");
1229  return false;
1230  }
1231 
1232  if (ik_seed_state.size() < num_joints_)
1233  {
1234  ROS_ERROR_STREAM("ik_seed_state only has " << ik_seed_state.size() << " entries, this ikfast solver requires "
1235  << num_joints_);
1236  return false;
1237  }
1238 
1239  KDL::Frame frame;
1240  tf::poseMsgToKDL(ik_poses[0], frame);
1241 
1242  // solving ik
1243  std::vector<IkSolutionList<IkReal>> solution_set;
1244  IkSolutionList<IkReal> ik_solutions;
1245  std::vector<double> vfree;
1246  int numsol = 0;
1247  std::vector<double> sampled_joint_vals;
1248  if (!redundant_joint_indices_.empty())
1249  {
1250  // initializing from seed
1251  sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]);
1252 
1253  // checking joint limits when using no discretization
1255  joint_has_limits_vector_[redundant_joint_indices_.front()])
1256  {
1257  double joint_min = joint_min_vector_[redundant_joint_indices_.front()];
1258  double joint_max = joint_max_vector_[redundant_joint_indices_.front()];
1259 
1260  double jv = sampled_joint_vals[0];
1261  if (!((jv > (joint_min - LIMIT_TOLERANCE)) && (jv < (joint_max + LIMIT_TOLERANCE))))
1262  {
1264  ROS_ERROR_STREAM("ik seed is out of bounds");
1265  return false;
1266  }
1267  }
1268 
1269  // computing all solutions sets for each sampled value of the redundant joint
1270  if (!sampleRedundantJoint(options.discretization_method, sampled_joint_vals))
1271  {
1273  return false;
1274  }
1275 
1276  for (unsigned int i = 0; i < sampled_joint_vals.size(); i++)
1277  {
1278  vfree.clear();
1279  vfree.push_back(sampled_joint_vals[i]);
1280  numsol += solve(frame, vfree, ik_solutions);
1281  solution_set.push_back(ik_solutions);
1282  }
1283  }
1284  else
1285  {
1286  // computing for single solution set
1287  numsol = solve(frame, vfree, ik_solutions);
1288  solution_set.push_back(ik_solutions);
1289  }
1290 
1291  ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast");
1292  bool solutions_found = false;
1293  if (numsol > 0)
1294  {
1295  /*
1296  Iterating through all solution sets and storing those that do not exceed joint limits.
1297  */
1298  for (unsigned int r = 0; r < solution_set.size(); r++)
1299  {
1300  ik_solutions = solution_set[r];
1301  numsol = ik_solutions.GetNumSolutions();
1302  for (int s = 0; s < numsol; ++s)
1303  {
1304  std::vector<double> sol;
1305  getSolution(ik_solutions, ik_seed_state, s, sol);
1306 
1307  bool obeys_limits = true;
1308  for (unsigned int i = 0; i < sol.size(); i++)
1309  {
1310  // Add tolerance to limit check
1311  if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1312  (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1313  {
1314  // One element of solution is not within limits
1315  obeys_limits = false;
1316  ROS_DEBUG_STREAM_NAMED(name_, "Not in limits! " << i << " value " << sol[i] << " has limit: "
1317  << joint_has_limits_vector_[i] << " being "
1318  << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
1319  break;
1320  }
1321  }
1322  if (obeys_limits)
1323  {
1324  // All elements of solution obey limits
1325  solutions_found = true;
1326  solutions.push_back(sol);
1327  }
1328  }
1329  }
1330 
1331  if (solutions_found)
1332  {
1334  return true;
1335  }
1336  }
1337  else
1338  {
1339  ROS_DEBUG_STREAM_NAMED(name_, "No IK solution");
1340  }
1341 
1343  return false;
1344 }
1345 
1347  std::vector<double>& sampled_joint_vals) const
1348 {
1349  double joint_min = -M_PI;
1350  double joint_max = M_PI;
1351  int index = redundant_joint_indices_.front();
1352  double joint_dscrt = redundant_joint_discretization_.at(index);
1353 
1354  if (joint_has_limits_vector_[redundant_joint_indices_.front()])
1355  {
1356  joint_min = joint_min_vector_[index];
1357  joint_max = joint_max_vector_[index];
1358  }
1359 
1360  switch (method)
1361  {
1363  {
1364  int steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1365  for (unsigned int i = 0; i < steps; i++)
1366  {
1367  sampled_joint_vals.push_back(joint_min + joint_dscrt * i);
1368  }
1369  sampled_joint_vals.push_back(joint_max);
1370  }
1371  break;
1373  {
1374  int steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1375  steps = steps > 0 ? steps : 1;
1376  double diff = joint_max - joint_min;
1377  for (int i = 0; i < steps; i++)
1378  {
1379  sampled_joint_vals.push_back(((diff * std::rand()) / (static_cast<double>(RAND_MAX))) + joint_min);
1380  }
1381  }
1382 
1383  break;
1385 
1386  break;
1387  default:
1388  ROS_ERROR_STREAM("Discretization method " << method << " is not supported");
1389  return false;
1390  }
1391 
1392  return true;
1393 }
1394 
1395 } // end namespace
1396 
1397 // register IKFastKinematicsPlugin as a KinematicsBase implementation
d
virtual const IkSolutionBase< T > & GetSolution(size_t index) const
returns the solution pointer
Definition: ikfast.h:283
KinematicError kinematic_error
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)
#define ROS_FATAL(...)
#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,...)
bool getCount(int &count, const int &max_count, const int &min_count) const
ROSCONSOLE_DECL void initialize()
virtual size_t GetNumSolutions() const
returns the number of solutions stored
Definition: ikfast.h:294
XmlRpcServer s
void getClosestSolution(const IkSolutionList< IkReal > &solutions, const std::vector< double > &ik_seed_state, std::vector< double > &solution) const
void setSearchDiscretization(const std::map< int, double > &discretization)
Sets the discretization value for the redundant joint.
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
IkParameterizationType
The types of inverse kinematics parameterizations supported.
The discrete solutions are returned in this structure.
Definition: ikfast.h:70
bool sampleRedundantJoint(kinematics::DiscretizationMethod method, std::vector< double > &sampled_joint_vals) const
samples the designated redundant joint using the chosen discretization method
const double LIMIT_TOLERANCE
end effector reaches desired 6D transformation
#define ROS_INFO_STREAM_NAMED(name, args)
#define M_PI
number of parameterizations (does not count IKP_None)
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...
PLUGINLIB_EXPORT_CLASS(ikfast_kinematics_plugin::IKFastKinematicsPlugin, kinematics::KinematicsBase)
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...
SEARCH_MODE
Search modes for searchPositionIK(), see there.
local point on end effector origin reaches desired 3D global point
direction on end effector coordinate system points to desired 3D position
Rotation M
#define ROS_DEBUG_NAMED(name,...)
bit is set if the data represents the time-derivate velocity of an IkParameterization ...
unsigned int index
bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices)
Overrides the default method to prevent changing the redundant joints.
#define ROS_WARN_STREAM_ONCE_NAMED(name, args)
#define ROS_FATAL_STREAM_NAMED(name, args)
options
IKFAST_API bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
double data[3]
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
DiscretizationMethod discretization_method
double harmonize(const std::vector< double > &ik_seed_state, std::vector< double > &solution) const
def xml_string(rootXml, addHeader=True)
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
void GetRPY(double &roll, double &pitch, double &yaw) const
virtual void GetSolution(T *solution, const T *freevalues) const =0
gets a concrete solution
end effector origin reaches desired 3D translation
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
Default implementation of IkSolutionListBase.
Definition: ikfast.h:273
ray on end effector coordinate system reaches desired global ray
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR_NAMED(name,...)
static Time now()
#define ROS_ERROR_STREAM(args)
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.
int solve(KDL::Frame &pose_frame, const std::vector< double > &vfree, IkSolutionList< IkReal > &solutions) const
Calls the IK solver from IKFast.
direction on end effector coordinate system reaches desired direction
r
#define ROS_ERROR(...)
IKFAST_API void ComputeFk(const IkReal *j, IkReal *eetrans, IkReal *eerot)
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.
#define ROS_WARN_STREAM_NAMED(name, args)
double data[9]


khi_duaro_ikfast_plugin
Author(s): matsui_hiro
autogenerated on Fri Mar 26 2021 02:34:14