fetch_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 Kinematics Solver Plugin for MoveIt! wrapping an ikfast solver from OpenRAVE.
38  *
39  * AUTO-GENERATED by create_ikfast_moveit_plugin.py in moveit_kinematics package.
40  *
41  * This file, including the ikfast cpp from OpenRAVE below, forms a MoveIt! kinematics plugin.
42  */
43 
44 #include <ros/ros.h>
47 #include <Eigen/Geometry>
48 #include <tf2_kdl/tf2_kdl.h>
49 #include <tf2_eigen/tf2_eigen.h>
51 
52 using namespace moveit::core;
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 
63 namespace fetch_arm
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,
94  IKP_TranslationZAxisAngle4D = 0x4400000d,
97 
101  IKP_TranslationYAxisAngleXNorm4D = 0x4400000f,
105  IKP_TranslationZAxisAngleYNorm4D = 0x44000010,
109 
114 
116  0x00008000,
133 
134  IKP_UniqueIdMask = 0x0000ffff,
135  IKP_CustomDataBit = 0x00010000,
136 };
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  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 
164  // The ikfast and base frame are the start and end of the kinematic chain for which the
165  // IKFast analytic solution was generated.
166  const std::string IKFAST_TIP_FRAME_ = "wrist_roll_link";
167  const std::string IKFAST_BASE_FRAME_ = "torso_lift_link";
168 
169  // The transform tip and base bool are set to true if this solver is used with a kinematic
170  // chain that extends beyond the ikfast tip and base frame. The solution will be valid so
171  // long as there are no active, passive, or mimic joints between either the ikfast_tip_frame
172  // and the tip_frame of the group or the ikfast_base_frame and the base_frame for the group.
173  bool tip_transform_required_;
174  bool base_transform_required_;
176  // We store the transform from the ikfast_base_frame to the group base_frame as well as the
177  // ikfast_tip_frame to the group tip_frame to transform input poses into the solver frame.
178  Eigen::Isometry3d chain_base_to_group_base_;
179  Eigen::Isometry3d group_tip_to_chain_tip_;
181  bool initialized_; // Internal variable that indicates whether solvers are configured and ready
182  const std::string name_{ "ikfast" };
183 
184  const std::vector<std::string>& getJointNames() const override
185  {
186  return joint_names_;
187  }
188  const std::vector<std::string>& getLinkNames() const override
189  {
190  return link_names_;
191  }
192 
193 public:
197  IKFastKinematicsPlugin() : num_joints_(GetNumJoints()), initialized_(false)
198  {
199  srand(time(nullptr));
200  supported_methods_.push_back(kinematics::DiscretizationMethods::NO_DISCRETIZATION);
201  supported_methods_.push_back(kinematics::DiscretizationMethods::ALL_DISCRETIZED);
202  supported_methods_.push_back(kinematics::DiscretizationMethods::ALL_RANDOM_SAMPLED);
203  }
204 
214  // Returns the IK solution that is within joint limits closest to ik_seed_state
215  bool getPositionIK(
216  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, std::vector<double>& solution,
217  moveit_msgs::MoveItErrorCodes& error_code,
219 
235  bool getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
236  std::vector<std::vector<double>>& solutions, kinematics::KinematicsResult& result,
237  const kinematics::KinematicsQueryOptions& options) const override;
238 
247  bool searchPositionIK(
248  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
249  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
251 
261  bool searchPositionIK(
262  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
263  const std::vector<double>& consistency_limits, std::vector<double>& solution,
264  moveit_msgs::MoveItErrorCodes& error_code,
266 
275  bool searchPositionIK(
276  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
277  std::vector<double>& solution, const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
279 
290  bool searchPositionIK(
291  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
292  const std::vector<double>& consistency_limits, std::vector<double>& solution,
293  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
295 
304  bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
305  std::vector<geometry_msgs::Pose>& poses) const override;
306 
316  void setSearchDiscretization(const std::map<unsigned int, double>& discretization);
317 
321  bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices) override;
322 
323 private:
324  bool initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name,
325  const std::string& base_frame, const std::vector<std::string>& tip_frames,
326  double search_discretization) override;
327 
332  size_t solve(KDL::Frame& pose_frame, const std::vector<double>& vfree, IkSolutionList<IkReal>& solutions) const;
333 
337  void getSolution(const IkSolutionList<IkReal>& solutions, int i, std::vector<double>& solution) const;
338 
342  void getSolution(const IkSolutionList<IkReal>& solutions, const std::vector<double>& ik_seed_state, int i,
343  std::vector<double>& solution) const;
344 
348  double enforceLimits(double val, double min, double max) const;
349 
350  void fillFreeParams(int count, int* array);
351  bool getCount(int& count, const int& max_count, const int& min_count) const;
352 
359  bool sampleRedundantJoint(kinematics::DiscretizationMethod method, std::vector<double>& sampled_joint_vals) const;
360 
362  bool computeRelativeTransform(const std::string& from, const std::string& to, Eigen::Isometry3d& transform,
363  bool& differs_from_identity);
370  void transformToChainFrame(const geometry_msgs::Pose& ik_pose, KDL::Frame& ik_pose_chain) const;
371 }; // end class
372 
373 bool IKFastKinematicsPlugin::computeRelativeTransform(const std::string& from, const std::string& to,
374  Eigen::Isometry3d& transform, bool& differs_from_identity)
375 {
376  RobotStatePtr robot_state;
377  robot_state.reset(new RobotState(robot_model_));
379  auto* from_link = robot_state->getLinkModel(from);
380  auto* to_link = robot_state->getLinkModel(to);
381  if (!from_link)
382  ROS_ERROR_STREAM_NAMED(name_, "Could not find frame " << from);
383  if (!to_link)
384  ROS_ERROR_STREAM_NAMED(name_, "Could not find frame " << to);
385  if (!from_link || !to_link)
386  return false;
388  if (robot_state->getRobotModel()->getRigidlyConnectedParentLinkModel(from_link) !=
389  robot_state->getRobotModel()->getRigidlyConnectedParentLinkModel(to_link))
390  {
391  ROS_ERROR_STREAM_NAMED(name_, "Link frames " << from << " and " << to << " are not rigidly connected.");
392  return false;
393  }
394 
395  transform = robot_state->getGlobalLinkTransform(from_link).inverse() * robot_state->getGlobalLinkTransform(to_link);
396  differs_from_identity = !transform.matrix().isIdentity();
397  return true;
398 }
399 
400 bool IKFastKinematicsPlugin::initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name,
401  const std::string& base_frame, const std::vector<std::string>& tip_frames,
402  double search_discretization)
403 {
404  if (tip_frames.size() != 1)
405  {
406  ROS_ERROR_NAMED(name_, "Expecting exactly one tip frame.");
407  return false;
408  }
409 
410  storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
411 
412  // This IKFast solution was generated with IKFAST_TIP_FRAME_ and IKFAST_BASE_FRAME_.
413  // It is often the case that fixed joints are added to these links to model things like
414  // a robot mounted on a table or a robot with an end effector attached to the last link.
415  // To support these use cases, we store the transform from the IKFAST_BASE_FRAME_ to the
416  // base_frame_ and IKFAST_TIP_FRAME_ the tip_frame_ and transform to the input pose accordingly
417  if (!computeRelativeTransform(tip_frames_[0], IKFAST_TIP_FRAME_, group_tip_to_chain_tip_, tip_transform_required_) ||
418  !computeRelativeTransform(IKFAST_BASE_FRAME_, base_frame_, chain_base_to_group_base_, base_transform_required_))
419  return false;
420 
421  // IKFast56/61
422  fillFreeParams(GetNumFreeParameters(), GetFreeParameters());
423 
424  if (free_params_.size() > 1)
425  {
426  ROS_ERROR_NAMED(name_, "Only one free joint parameter supported!");
427  return false;
428  }
429  else if (free_params_.size() == 1)
430  {
431  redundant_joint_indices_.clear();
432  redundant_joint_indices_.push_back(free_params_[0]);
433  KinematicsBase::setSearchDiscretization(search_discretization);
434  }
435 
436  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group_name);
437  if (!jmg)
438  {
439  ROS_ERROR_STREAM_NAMED(name_, "Unknown planning group: " << group_name);
440  return false;
441  }
442 
443  ROS_DEBUG_STREAM_NAMED(name_, "Registering joints and links");
444  const moveit::core::LinkModel* link = robot_model_->getLinkModel(tip_frames_[0]);
445  const moveit::core::LinkModel* base_link = robot_model_->getLinkModel(base_frame_);
446  while (link && link != base_link)
447  {
448  ROS_DEBUG_STREAM_NAMED(name_, "Link " << link->getName());
449  link_names_.push_back(link->getName());
450  const moveit::core::JointModel* joint = link->getParentJointModel();
451  if (joint->getType() != joint->UNKNOWN && joint->getType() != joint->FIXED && joint->getVariableCount() == 1)
452  {
453  ROS_DEBUG_STREAM_NAMED(name_, "Adding joint " << joint->getName());
454 
455  joint_names_.push_back(joint->getName());
456  const moveit::core::VariableBounds& bounds = joint->getVariableBounds()[0];
457  joint_has_limits_vector_.push_back(bounds.position_bounded_);
458  joint_min_vector_.push_back(bounds.min_position_);
459  joint_max_vector_.push_back(bounds.max_position_);
460  }
461  link = link->getParentLinkModel();
462  }
463 
464  if (joint_names_.size() != num_joints_)
465  {
466  ROS_FATAL_NAMED(name_, "Joint numbers of RobotModel (%zd) and IKFast solver (%zd) do not match",
467  joint_names_.size(), num_joints_);
468  return false;
469  }
470 
471  std::reverse(link_names_.begin(), link_names_.end());
472  std::reverse(joint_names_.begin(), joint_names_.end());
473  std::reverse(joint_min_vector_.begin(), joint_min_vector_.end());
474  std::reverse(joint_max_vector_.begin(), joint_max_vector_.end());
475  std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end());
476 
477  for (size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
478  ROS_DEBUG_STREAM_NAMED(name_, joint_names_[joint_id] << " " << joint_min_vector_[joint_id] << " "
479  << joint_max_vector_[joint_id] << " "
480  << joint_has_limits_vector_[joint_id]);
481 
482  initialized_ = true;
483  return true;
484 }
485 
486 void IKFastKinematicsPlugin::setSearchDiscretization(const std::map<unsigned int, double>& discretization)
487 {
488  if (discretization.empty())
489  {
490  ROS_ERROR("The 'discretization' map is empty");
491  return;
492  }
493 
494  if (redundant_joint_indices_.empty())
495  {
496  ROS_ERROR_STREAM_NAMED(name_, "This group's solver doesn't support redundant joints");
497  return;
498  }
499 
500  if (discretization.begin()->first != redundant_joint_indices_[0])
501  {
502  std::string redundant_joint = joint_names_[free_params_[0]];
503  ROS_ERROR_STREAM_NAMED(name_, "Attempted to discretize a non-redundant joint "
504  << discretization.begin()->first << ", only joint '" << redundant_joint
505  << "' with index " << redundant_joint_indices_[0] << " is redundant.");
506  return;
507  }
508 
509  if (discretization.begin()->second <= 0.0)
510  {
511  ROS_ERROR_STREAM_NAMED(name_, "Discretization can not takes values that are <= 0");
512  return;
513  }
514 
515  redundant_joint_discretization_.clear();
516  redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second;
517 }
518 
519 bool IKFastKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices)
520 {
521  ROS_ERROR_STREAM_NAMED(name_, "Changing the redundant joints isn't permitted by this group's solver ");
522  return false;
523 }
524 
525 size_t IKFastKinematicsPlugin::solve(KDL::Frame& pose_frame, const std::vector<double>& vfree,
526  IkSolutionList<IkReal>& solutions) const
527 {
528  // IKFast56/61
529  solutions.Clear();
530 
531  double trans[3];
532  trans[0] = pose_frame.p[0]; //-.18;
533  trans[1] = pose_frame.p[1];
534  trans[2] = pose_frame.p[2];
535 
536  KDL::Rotation mult;
537  KDL::Vector direction;
538 
539  switch (GetIkType())
540  {
541  case IKP_Transform6D:
542  case IKP_Translation3D:
543  // For **Transform6D**, eerot is 9 values for the 3x3 rotation matrix. For **Translation3D**, these are ignored.
544 
545  mult = pose_frame.M;
546 
547  double vals[9];
548  vals[0] = mult(0, 0);
549  vals[1] = mult(0, 1);
550  vals[2] = mult(0, 2);
551  vals[3] = mult(1, 0);
552  vals[4] = mult(1, 1);
553  vals[5] = mult(1, 2);
554  vals[6] = mult(2, 0);
555  vals[7] = mult(2, 1);
556  vals[8] = mult(2, 2);
557 
558  // IKFast56/61
559  ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
560  return solutions.GetNumSolutions();
561 
562  case IKP_Direction3D:
563  case IKP_Ray4D:
565  // For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target
566  // direction.
567 
568  direction = pose_frame.M * KDL::Vector(0, 0, 1);
569  ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
570  return solutions.GetNumSolutions();
571 
575  // For *TranslationXAxisAngle4D*, *TranslationYAxisAngle4D*, *TranslationZAxisAngle4D* - end effector origin
576  // reaches desired 3D translation, manipulator direction makes a specific angle with x/y/z-axis (defined in the
577  // manipulator base link’s coordinate system)
578  ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet.");
579  return 0;
580 
582  // For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end
583  // effector coordinate system.
584  ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet.");
585  return 0;
586 
587  case IKP_Rotation3D:
588  case IKP_Lookat3D:
589  case IKP_TranslationXY2D:
591  ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet.");
592  return 0;
593 
595  double roll, pitch, yaw;
596  // For **TranslationXAxisAngleZNorm4D** - end effector origin reaches desired 3D translation, manipulator
597  // direction needs to be orthogonal to z axis and be rotated at a certain angle starting from the x axis (defined
598  // in the manipulator base link’s coordinate system)
599  pose_frame.M.GetRPY(roll, pitch, yaw);
600  ComputeIk(trans, &yaw, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
601  return solutions.GetNumSolutions();
602 
604  // For **TranslationYAxisAngleXNorm4D** - end effector origin reaches desired 3D translation, manipulator
605  // direction needs to be orthogonal to x axis and be rotated at a certain angle starting from the y axis (defined
606  // in the manipulator base link’s coordinate system)
607  pose_frame.M.GetRPY(roll, pitch, yaw);
608  ComputeIk(trans, &roll, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
609  return solutions.GetNumSolutions();
610 
612  // For **TranslationZAxisAngleYNorm4D** - end effector origin reaches desired 3D translation, manipulator
613  // direction needs to be orthogonal to y axis and be rotated at a certain angle starting from the z axis (defined
614  // in the manipulator base link’s coordinate system)
615  pose_frame.M.GetRPY(roll, pitch, yaw);
616  ComputeIk(trans, &pitch, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
617  return solutions.GetNumSolutions();
618 
619  default:
620  ROS_ERROR_NAMED(name_, "Unknown IkParameterizationType! "
621  "Was the solver generated with an incompatible version of Openrave?");
622  return 0;
623  }
624 }
625 
626 void IKFastKinematicsPlugin::getSolution(const IkSolutionList<IkReal>& solutions, int i,
627  std::vector<double>& solution) const
628 {
629  solution.clear();
630  solution.resize(num_joints_);
631 
632  // IKFast56/61
633  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
634  std::vector<IkReal> vsolfree(sol.GetFree().size());
635  sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : nullptr);
636 
637  for (std::size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
638  {
639  if (joint_has_limits_vector_[joint_id])
640  {
641  solution[joint_id] = enforceLimits(solution[joint_id], joint_min_vector_[joint_id], joint_max_vector_[joint_id]);
642  }
643  }
644 }
645 
646 void IKFastKinematicsPlugin::getSolution(const IkSolutionList<IkReal>& solutions,
647  const std::vector<double>& ik_seed_state, int i,
648  std::vector<double>& solution) const
649 {
650  solution.clear();
651  solution.resize(num_joints_);
652 
653  // IKFast56/61
654  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
655  std::vector<IkReal> vsolfree(sol.GetFree().size());
656  sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : nullptr);
657 
658  // rotate joints by +/-360° where it is possible and useful
659  for (std::size_t i = 0; i < num_joints_; ++i)
660  {
661  if (joint_has_limits_vector_[i])
662  {
663  solution[i] = enforceLimits(solution[i], joint_min_vector_[i], joint_max_vector_[i]);
664  double signed_distance = solution[i] - ik_seed_state[i];
665  while (signed_distance > M_PI && solution[i] - 2 * M_PI > (joint_min_vector_[i] - LIMIT_TOLERANCE))
666  {
667  signed_distance -= 2 * M_PI;
668  solution[i] -= 2 * M_PI;
669  }
670  while (signed_distance < -M_PI && solution[i] + 2 * M_PI < (joint_max_vector_[i] + LIMIT_TOLERANCE))
671  {
672  signed_distance += 2 * M_PI;
673  solution[i] += 2 * M_PI;
674  }
675  }
676  }
677 }
678 
679 double IKFastKinematicsPlugin::enforceLimits(double joint_value, double min, double max) const
680 {
681  // If the joint_value is greater than max subtract 2 * PI until it is less than the max
682  while (joint_value > max)
683  {
684  joint_value -= 2 * M_PI;
685  }
686 
687  // If the joint_value is less than the min, add 2 * PI until it is more than the min
688  while (joint_value < min)
689  {
690  joint_value += 2 * M_PI;
691  }
692  return joint_value;
693 }
694 
695 void IKFastKinematicsPlugin::fillFreeParams(int count, int* array)
696 {
697  free_params_.clear();
698  for (int i = 0; i < count; ++i)
699  free_params_.push_back(array[i]);
700 }
701 
702 bool IKFastKinematicsPlugin::getCount(int& count, const int& max_count, const int& min_count) const
703 {
704  if (count > 0)
705  {
706  if (-count >= min_count)
707  {
708  count = -count;
709  return true;
710  }
711  else if (count + 1 <= max_count)
712  {
713  count = count + 1;
714  return true;
715  }
716  else
717  {
718  return false;
719  }
720  }
721  else
722  {
723  if (1 - count <= max_count)
724  {
725  count = 1 - count;
726  return true;
727  }
728  else if (count - 1 >= min_count)
729  {
730  count = count - 1;
731  return true;
732  }
733  else
734  return false;
735  }
736 }
737 
738 bool IKFastKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
739  const std::vector<double>& joint_angles,
740  std::vector<geometry_msgs::Pose>& poses) const
741 {
742  if (GetIkType() != IKP_Transform6D)
743  {
744  // ComputeFk() is the inverse function of ComputeIk(), so the format of
745  // eerot differs depending on IK type. The Transform6D IK type is the only
746  // one for which a 3x3 rotation matrix is returned, which means we can only
747  // compute FK for that IK type.
748  ROS_ERROR_NAMED(name_, "Can only compute FK for Transform6D IK type!");
749  return false;
750  }
751 
752  KDL::Frame p_out;
753  if (link_names.size() == 0)
754  {
755  ROS_WARN_STREAM_NAMED(name_, "Link names with nothing");
756  return false;
757  }
758 
759  if (link_names.size() != 1 || link_names[0] != getTipFrame())
760  {
761  ROS_ERROR_NAMED(name_, "Can compute FK for %s only", getTipFrame().c_str());
762  return false;
763  }
764 
765  bool valid = true;
766 
767  IkReal eerot[9], eetrans[3];
768 
769  if (joint_angles.size() != num_joints_)
770  {
771  ROS_ERROR_NAMED(name_, "Unexpected number of joint angles");
772  return false;
773  }
774 
775  IkReal angles[num_joints_];
776  for (unsigned char i = 0; i < num_joints_; i++)
777  angles[i] = joint_angles[i];
778 
779  // IKFast56/61
780  ComputeFk(angles, eetrans, eerot);
781 
782  for (int i = 0; i < 3; ++i)
783  p_out.p.data[i] = eetrans[i];
784 
785  for (int i = 0; i < 9; ++i)
786  p_out.M.data[i] = eerot[i];
787 
788  poses.resize(1);
789  poses[0] = tf2::toMsg(p_out);
790 
791  return valid;
792 }
793 
794 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
795  const std::vector<double>& ik_seed_state, double timeout,
796  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
797  const kinematics::KinematicsQueryOptions& options) const
798 {
799  std::vector<double> consistency_limits;
800  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
801  options);
802 }
803 
804 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
805  const std::vector<double>& ik_seed_state, double timeout,
806  const std::vector<double>& consistency_limits,
807  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
808  const kinematics::KinematicsQueryOptions& options) const
809 {
810  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
811  options);
812 }
813 
814 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
815  const std::vector<double>& ik_seed_state, double timeout,
816  std::vector<double>& solution, const IKCallbackFn& solution_callback,
817  moveit_msgs::MoveItErrorCodes& error_code,
818  const kinematics::KinematicsQueryOptions& options) const
819 {
820  std::vector<double> consistency_limits;
821  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
822  options);
823 }
824 
825 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
826  const std::vector<double>& ik_seed_state, double timeout,
827  const std::vector<double>& consistency_limits,
828  std::vector<double>& solution, const IKCallbackFn& solution_callback,
829  moveit_msgs::MoveItErrorCodes& error_code,
830  const kinematics::KinematicsQueryOptions& options) const
831 {
832  // "SEARCH_MODE" is fixed during code generation
833  SEARCH_MODE search_mode = OPTIMIZE_MAX_JOINT;
834 
835  // Check if there are no redundant joints
836  if (free_params_.size() == 0)
837  {
838  ROS_DEBUG_STREAM_NAMED(name_, "No need to search since no free params/redundant joints");
839 
840  std::vector<geometry_msgs::Pose> ik_poses(1, ik_pose);
841  std::vector<std::vector<double>> solutions;
842  kinematics::KinematicsResult kinematic_result;
843  // Find all IK solutions within joint limits
844  if (!getPositionIK(ik_poses, ik_seed_state, solutions, kinematic_result, options))
845  {
846  ROS_DEBUG_STREAM_NAMED(name_, "No solution whatsoever");
847  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
848  return false;
849  }
850 
851  // sort solutions by their distance to the seed
852  std::vector<LimitObeyingSol> solutions_obey_limits;
853  for (std::size_t i = 0; i < solutions.size(); ++i)
854  {
855  double dist_from_seed = 0.0;
856  for (std::size_t j = 0; j < ik_seed_state.size(); ++j)
857  {
858  dist_from_seed += fabs(ik_seed_state[j] - solutions[i][j]);
859  }
860 
861  solutions_obey_limits.push_back({ solutions[i], dist_from_seed });
862  }
863  std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
864 
865  // check for collisions if a callback is provided
866  if (!solution_callback.empty())
867  {
868  for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i)
869  {
870  solution_callback(ik_pose, solutions_obey_limits[i].value, error_code);
871  if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
872  {
873  solution = solutions_obey_limits[i].value;
874  ROS_DEBUG_STREAM_NAMED(name_, "Solution passes callback");
875  return true;
876  }
877  }
878 
879  ROS_DEBUG_STREAM_NAMED(name_, "Solution has error code " << error_code);
880  return false;
881  }
882  else
883  {
884  solution = solutions_obey_limits[0].value;
885  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
886  return true; // no collision check callback provided
887  }
888  }
889 
890  // -------------------------------------------------------------------------------------------------
891  // Error Checking
892  if (!initialized_)
893  {
894  ROS_ERROR_STREAM_NAMED(name_, "Kinematics not active");
895  error_code.val = error_code.NO_IK_SOLUTION;
896  return false;
897  }
898 
899  if (ik_seed_state.size() != num_joints_)
900  {
901  ROS_ERROR_STREAM_NAMED(name_, "Seed state must have size " << num_joints_ << " instead of size "
902  << ik_seed_state.size());
903  error_code.val = error_code.NO_IK_SOLUTION;
904  return false;
905  }
906 
907  if (!consistency_limits.empty() && consistency_limits.size() != num_joints_)
908  {
909  ROS_ERROR_STREAM_NAMED(name_, "Consistency limits be empty or must have size " << num_joints_ << " instead of size "
910  << consistency_limits.size());
911  error_code.val = error_code.NO_IK_SOLUTION;
912  return false;
913  }
914 
915  // -------------------------------------------------------------------------------------------------
916  // Initialize
917 
918  KDL::Frame frame;
919  transformToChainFrame(ik_pose, frame);
920 
921  std::vector<double> vfree(free_params_.size());
922 
923  int counter = 0;
924 
925  double initial_guess = ik_seed_state[free_params_[0]];
926  vfree[0] = initial_guess;
927 
928  // -------------------------------------------------------------------------------------------------
929  // Handle consitency limits if needed
930  int num_positive_increments;
931  int num_negative_increments;
932  double search_discretization = redundant_joint_discretization_.at(free_params_[0]);
933 
934  if (!consistency_limits.empty())
935  {
936  // MoveIt! replaced consistency_limit (scalar) w/ consistency_limits (vector)
937  // Assume [0]th free_params element for now. Probably wrong.
938  double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess + consistency_limits[free_params_[0]]);
939  double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess - consistency_limits[free_params_[0]]);
940 
941  num_positive_increments = static_cast<int>((max_limit - initial_guess) / search_discretization);
942  num_negative_increments = static_cast<int>((initial_guess - min_limit) / search_discretization);
943  }
944  else // no consistency limits provided
945  {
946  num_positive_increments = (joint_max_vector_[free_params_[0]] - initial_guess) / search_discretization;
947  num_negative_increments = (initial_guess - joint_min_vector_[free_params_[0]]) / search_discretization;
948  }
949 
950  // -------------------------------------------------------------------------------------------------
951  // Begin searching
952 
953  ROS_DEBUG_STREAM_NAMED(name_, "Free param is " << free_params_[0] << " initial guess is " << initial_guess
954  << ", # positive increments: " << num_positive_increments
955  << ", # negative increments: " << num_negative_increments);
956  if ((search_mode & OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000)
957  ROS_WARN_STREAM_ONCE_NAMED(name_, "Large search space, consider increasing the search discretization");
958 
959  double best_costs = -1.0;
960  std::vector<double> best_solution;
961  int nattempts = 0, nvalid = 0;
962 
963  while (true)
964  {
965  IkSolutionList<IkReal> solutions;
966  size_t numsol = solve(frame, vfree, solutions);
967 
968  ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast");
969 
970  if (numsol > 0)
971  {
972  for (size_t s = 0; s < numsol; ++s)
973  {
974  nattempts++;
975  std::vector<double> sol;
976  getSolution(solutions, ik_seed_state, s, sol);
977 
978  bool obeys_limits = true;
979  for (size_t i = 0; i < sol.size(); i++)
980  {
981  if (joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
982  {
983  obeys_limits = false;
984  break;
985  }
986  // ROS_INFO_STREAM_NAMED(name_,"Num " << i << " value " << sol[i] << " has limits " <<
987  // joint_has_limits_vector_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i]);
988  }
989  if (obeys_limits)
990  {
991  getSolution(solutions, ik_seed_state, s, solution);
992 
993  // This solution is within joint limits, now check if in collision (if callback provided)
994  if (!solution_callback.empty())
995  {
996  solution_callback(ik_pose, solution, error_code);
997  }
998  else
999  {
1000  error_code.val = error_code.SUCCESS;
1001  }
1002 
1003  if (error_code.val == error_code.SUCCESS)
1004  {
1005  nvalid++;
1006  if (search_mode & OPTIMIZE_MAX_JOINT)
1007  {
1008  // Costs for solution: Largest joint motion
1009  double costs = 0.0;
1010  for (unsigned int i = 0; i < solution.size(); i++)
1011  {
1012  double d = fabs(ik_seed_state[i] - solution[i]);
1013  if (d > costs)
1014  costs = d;
1015  }
1016  if (costs < best_costs || best_costs == -1.0)
1017  {
1018  best_costs = costs;
1019  best_solution = solution;
1020  }
1021  }
1022  else
1023  // Return first feasible solution
1024  return true;
1025  }
1026  }
1027  }
1028  }
1029 
1030  if (!getCount(counter, num_positive_increments, -num_negative_increments))
1031  {
1032  // Everything searched
1033  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1034  break;
1035  }
1036 
1037  vfree[0] = initial_guess + search_discretization * counter;
1038  // ROS_DEBUG_STREAM_NAMED(name_,"Attempt " << counter << " with 0th free joint having value " << vfree[0]);
1039  }
1040 
1041  ROS_DEBUG_STREAM_NAMED(name_, "Valid solutions: " << nvalid << "/" << nattempts);
1042 
1043  if ((search_mode & OPTIMIZE_MAX_JOINT) && best_costs != -1.0)
1044  {
1045  solution = best_solution;
1046  error_code.val = error_code.SUCCESS;
1047  return true;
1048  }
1049 
1050  // No solution found
1051  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1052  return false;
1053 }
1054 
1055 // Used when there are no redundant joints - aka no free params
1056 bool IKFastKinematicsPlugin::getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
1057  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
1058  const kinematics::KinematicsQueryOptions& options) const
1059 {
1060  ROS_DEBUG_STREAM_NAMED(name_, "getPositionIK");
1061 
1062  if (!initialized_)
1063  {
1064  ROS_ERROR_NAMED(name_, "kinematics not active");
1065  return false;
1066  }
1067 
1068  if (ik_seed_state.size() < num_joints_)
1069  {
1070  ROS_ERROR_STREAM_NAMED(name_, "ik_seed_state only has " << ik_seed_state.size()
1071  << " entries, this ikfast solver requires " << num_joints_);
1072  return false;
1073  }
1074 
1075  // Check if seed is in bound
1076  for (std::size_t i = 0; i < ik_seed_state.size(); i++)
1077  {
1078  // Add tolerance to limit check
1079  if (joint_has_limits_vector_[i] && ((ik_seed_state[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1080  (ik_seed_state[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1081  {
1082  ROS_DEBUG_STREAM_NAMED(name_, "IK seed not in limits! " << static_cast<int>(i) << " value " << ik_seed_state[i]
1083  << " has limit: " << joint_has_limits_vector_[i]
1084  << " being " << joint_min_vector_[i] << " to "
1085  << joint_max_vector_[i]);
1086  return false;
1087  }
1088  }
1089 
1090  std::vector<double> vfree(free_params_.size());
1091  for (std::size_t i = 0; i < free_params_.size(); ++i)
1092  {
1093  int p = free_params_[i];
1094  ROS_ERROR("%u is %f", p, ik_seed_state[p]); // DTC
1095  vfree[i] = ik_seed_state[p];
1096  }
1097 
1098  KDL::Frame frame;
1099  transformToChainFrame(ik_pose, frame);
1100 
1101  IkSolutionList<IkReal> solutions;
1102  size_t numsol = solve(frame, vfree, solutions);
1103  ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast");
1104 
1105  std::vector<LimitObeyingSol> solutions_obey_limits;
1106 
1107  if (numsol)
1108  {
1109  std::vector<double> solution_obey_limits;
1110  for (std::size_t s = 0; s < numsol; ++s)
1111  {
1112  std::vector<double> sol;
1113  getSolution(solutions, ik_seed_state, s, sol);
1114  ROS_DEBUG_NAMED(name_, "Sol %d: %e %e %e %e %e %e", static_cast<int>(s), sol[0], sol[1], sol[2], sol[3],
1115  sol[4], sol[5]);
1116 
1117  bool obeys_limits = true;
1118  for (std::size_t i = 0; i < sol.size(); i++)
1119  {
1120  // Add tolerance to limit check
1121  if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1122  (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1123  {
1124  // One element of solution is not within limits
1125  obeys_limits = false;
1126  ROS_DEBUG_STREAM_NAMED(name_, "Not in limits! " << static_cast<int>(i) << " value " << sol[i]
1127  << " has limit: " << joint_has_limits_vector_[i]
1128  << " being " << joint_min_vector_[i] << " to "
1129  << joint_max_vector_[i]);
1130  break;
1131  }
1132  }
1133  if (obeys_limits)
1134  {
1135  // All elements of this solution obey limits
1136  getSolution(solutions, ik_seed_state, s, solution_obey_limits);
1137  double dist_from_seed = 0.0;
1138  for (std::size_t i = 0; i < ik_seed_state.size(); ++i)
1139  {
1140  dist_from_seed += fabs(ik_seed_state[i] - solution_obey_limits[i]);
1141  }
1142 
1143  solutions_obey_limits.push_back({ solution_obey_limits, dist_from_seed });
1144  }
1145  }
1146  }
1147  else
1148  {
1149  ROS_DEBUG_STREAM_NAMED(name_, "No IK solution");
1150  }
1151 
1152  // Sort the solutions under limits and find the one that is closest to ik_seed_state
1153  if (!solutions_obey_limits.empty())
1154  {
1155  std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
1156  solution = solutions_obey_limits[0].value;
1157  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
1158  return true;
1159  }
1160 
1161  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1162  return false;
1163 }
1164 
1165 bool IKFastKinematicsPlugin::getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses,
1166  const std::vector<double>& ik_seed_state,
1167  std::vector<std::vector<double>>& solutions,
1169  const kinematics::KinematicsQueryOptions& options) const
1170 {
1171  ROS_DEBUG_STREAM_NAMED(name_, "getPositionIK with multiple solutions");
1172 
1173  if (!initialized_)
1174  {
1175  ROS_ERROR_NAMED(name_, "kinematics not active");
1177  return false;
1178  }
1179 
1180  if (ik_poses.empty())
1181  {
1182  ROS_ERROR_NAMED(name_, "ik_poses is empty");
1184  return false;
1185  }
1186 
1187  if (ik_poses.size() > 1)
1188  {
1189  ROS_ERROR_NAMED(name_, "ik_poses contains multiple entries, only one is allowed");
1191  return false;
1192  }
1193 
1194  if (ik_seed_state.size() < num_joints_)
1195  {
1196  ROS_ERROR_STREAM_NAMED(name_, "ik_seed_state only has " << ik_seed_state.size()
1197  << " entries, this ikfast solver requires " << num_joints_);
1198  return false;
1199  }
1200 
1201  KDL::Frame frame;
1202  transformToChainFrame(ik_poses[0], frame);
1203 
1204  // solving ik
1205  std::vector<IkSolutionList<IkReal>> solution_set;
1206  IkSolutionList<IkReal> ik_solutions;
1207  std::vector<double> vfree;
1208  int numsol = 0;
1209  std::vector<double> sampled_joint_vals;
1210  if (!redundant_joint_indices_.empty())
1211  {
1212  // initializing from seed
1213  sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]);
1214 
1215  // checking joint limits when using no discretization
1217  joint_has_limits_vector_[redundant_joint_indices_.front()])
1218  {
1219  double joint_min = joint_min_vector_[redundant_joint_indices_.front()];
1220  double joint_max = joint_max_vector_[redundant_joint_indices_.front()];
1221 
1222  double jv = sampled_joint_vals[0];
1223  if (!((jv > (joint_min - LIMIT_TOLERANCE)) && (jv < (joint_max + LIMIT_TOLERANCE))))
1224  {
1226  ROS_ERROR_STREAM_NAMED(name_, "ik seed is out of bounds");
1227  return false;
1228  }
1229  }
1230 
1231  // computing all solutions sets for each sampled value of the redundant joint
1232  if (!sampleRedundantJoint(options.discretization_method, sampled_joint_vals))
1233  {
1235  return false;
1236  }
1237 
1238  for (unsigned int i = 0; i < sampled_joint_vals.size(); i++)
1239  {
1240  vfree.clear();
1241  vfree.push_back(sampled_joint_vals[i]);
1242  numsol += solve(frame, vfree, ik_solutions);
1243  solution_set.push_back(ik_solutions);
1244  }
1245  }
1246  else
1247  {
1248  // computing for single solution set
1249  numsol = solve(frame, vfree, ik_solutions);
1250  solution_set.push_back(ik_solutions);
1251  }
1252 
1253  ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast");
1254  bool solutions_found = false;
1255  if (numsol > 0)
1256  {
1257  /*
1258  Iterating through all solution sets and storing those that do not exceed joint limits.
1259  */
1260  for (unsigned int r = 0; r < solution_set.size(); r++)
1261  {
1262  ik_solutions = solution_set[r];
1263  numsol = ik_solutions.GetNumSolutions();
1264  for (int s = 0; s < numsol; ++s)
1265  {
1266  std::vector<double> sol;
1267  getSolution(ik_solutions, ik_seed_state, s, sol);
1268 
1269  bool obeys_limits = true;
1270  for (unsigned int i = 0; i < sol.size(); i++)
1271  {
1272  // Add tolerance to limit check
1273  if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1274  (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1275  {
1276  // One element of solution is not within limits
1277  obeys_limits = false;
1278  ROS_DEBUG_STREAM_NAMED(name_, "Not in limits! " << i << " value " << sol[i] << " has limit: "
1279  << joint_has_limits_vector_[i] << " being "
1280  << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
1281  break;
1282  }
1283  }
1284  if (obeys_limits)
1285  {
1286  // All elements of solution obey limits
1287  solutions_found = true;
1288  solutions.push_back(sol);
1289  }
1290  }
1291  }
1292 
1293  if (solutions_found)
1294  {
1296  return true;
1297  }
1298  }
1299  else
1300  {
1301  ROS_DEBUG_STREAM_NAMED(name_, "No IK solution");
1302  }
1303 
1305  return false;
1306 }
1307 
1308 bool IKFastKinematicsPlugin::sampleRedundantJoint(kinematics::DiscretizationMethod method,
1309  std::vector<double>& sampled_joint_vals) const
1310 {
1311  int index = redundant_joint_indices_.front();
1312  double joint_dscrt = redundant_joint_discretization_.at(index);
1313  double joint_min = joint_min_vector_[index];
1314  double joint_max = joint_max_vector_[index];
1315 
1316  switch (method)
1317  {
1319  {
1320  size_t steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1321  for (size_t i = 0; i < steps; i++)
1322  {
1323  sampled_joint_vals.push_back(joint_min + joint_dscrt * i);
1324  }
1325  sampled_joint_vals.push_back(joint_max);
1326  }
1327  break;
1329  {
1330  int steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1331  steps = steps > 0 ? steps : 1;
1332  double diff = joint_max - joint_min;
1333  for (int i = 0; i < steps; i++)
1334  {
1335  sampled_joint_vals.push_back(((diff * std::rand()) / (static_cast<double>(RAND_MAX))) + joint_min);
1336  }
1337  }
1338 
1339  break;
1341 
1342  break;
1343  default:
1344  ROS_ERROR_STREAM_NAMED(name_, "Discretization method " << method << " is not supported");
1345  return false;
1346  }
1347 
1348  return true;
1349 }
1350 
1351 void IKFastKinematicsPlugin::transformToChainFrame(const geometry_msgs::Pose& ik_pose, KDL::Frame& ik_pose_chain) const
1352 {
1353  if (tip_transform_required_ || base_transform_required_)
1354  {
1355  Eigen::Isometry3d ik_eigen_pose;
1356  tf2::fromMsg(ik_pose, ik_eigen_pose);
1357  if (tip_transform_required_)
1358  ik_eigen_pose = ik_eigen_pose * group_tip_to_chain_tip_;
1359 
1360  if (base_transform_required_)
1361  ik_eigen_pose = chain_base_to_group_base_ * ik_eigen_pose;
1362 
1363  tf::transformEigenToKDL(ik_eigen_pose, ik_pose_chain);
1364  }
1365  else
1366  {
1367  tf2::fromMsg(ik_pose, ik_pose_chain);
1368  }
1369 }
1370 
1371 } // end namespace
1372 
1373 // register IKFastKinematicsPlugin as a KinematicsBase implementation
d
KinematicError kinematic_error
SEARCH_MODE
Search modes for searchPositionIK(), see there.
end effector reaches desired 6D transformation
direction on end effector coordinate system points to desired 3D position
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
bool operator<(const LimitObeyingSol &a) const
void GetRPY(double &roll, double &pitch, double &yaw) const
ROSCONSOLE_DECL void initialize()
const JointModel * getParentJointModel() const
XmlRpcServer s
end effector reaches desired 3D rotation
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
virtual const IkSolutionBase< T > & GetSolution(size_t index) const
returns the solution pointer
Definition: ikfast.h:283
The discrete solutions are returned in this structure.
Definition: ikfast.h:70
#define ROS_ERROR(...)
const double LIMIT_TOLERANCE
end effector origin reaches desired 3D translation
#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...
void transformEigenToKDL(const Eigen::Affine3d &e, KDL::Frame &k)
Rotation M
IKFAST_API bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
#define ROS_DEBUG_NAMED(name,...)
unsigned int index
const LinkModel * getParentLinkModel() const
IKFAST_API int GetIkType()
#define ROS_WARN_STREAM_ONCE_NAMED(name, args)
options
double data[3]
void fromMsg(const A &, B &b)
std::size_t getVariableCount() const
PLUGINLIB_EXPORT_CLASS(fetch_arm::IKFastKinematicsPlugin, kinematics::KinematicsBase)
DiscretizationMethod discretization_method
const std::string & getName() const
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
const std::vector< std::string > & getLinkNames() const override
virtual void GetSolution(T *solution, const T *freevalues) const =0
gets a concrete solution
B toMsg(const A &a)
const VariableBounds & getVariableBounds(const std::string &variable) const
IKFAST_API int GetNumJoints()
ray on end effector coordinate system reaches desired global ray
IKFAST_API int * GetFreeParameters()
IKFAST_API void ComputeFk(const IkReal *j, IkReal *eetrans, IkReal *eerot)
Default implementation of IkSolutionListBase.
Definition: ikfast.h:273
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR_NAMED(name,...)
const std::vector< std::string > & getJointNames() const override
IKFAST_API int GetNumFreeParameters()
direction on end effector coordinate system reaches desired direction
bit is set if the data represents the time-derivate velocity of an IkParameterization ...
r
IkParameterizationType
The types of inverse kinematics parameterizations supported.
virtual size_t GetNumSolutions() const
returns the number of solutions stored
Definition: ikfast.h:294
JointType getType() const
local point on end effector origin reaches desired 3D global point
#define ROS_WARN_STREAM_NAMED(name, args)
double data[9]
number of parameterizations (does not count IKP_None)
const std::string & getName() const


fetch_ikfast_plugin
Author(s): Michael Ferguson
autogenerated on Mon Feb 28 2022 22:23:56