ikfast61_moveit_plugin_template.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>
50 
51 using namespace moveit::core;
52 
53 // Need a floating point tolerance when checking joint limits, in case the joint starts at limit
54 const double LIMIT_TOLERANCE = .0000001;
57 {
60 };
61 
62 namespace _NAMESPACE_
63 {
64 #define IKFAST_NO_MAIN // Don't include main() from IKFast
65 
72 {
73  IKP_None = 0,
74  IKP_Transform6D = 0x67000001,
75  IKP_Rotation3D = 0x34000002,
76  IKP_Translation3D = 0x33000003,
77  IKP_Direction3D = 0x23000004,
78  IKP_Ray4D = 0x46000005,
79  IKP_Lookat3D = 0x23000006,
81  IKP_TranslationXY2D = 0x22000008,
85  IKP_TranslationLocalGlobal6D = 0x3600000a,
88 
90  IKP_TranslationYAxisAngle4D = 0x4400000c,
93  IKP_TranslationZAxisAngle4D = 0x4400000d,
96 
100  IKP_TranslationYAxisAngleXNorm4D = 0x4400000f,
104  IKP_TranslationZAxisAngleYNorm4D = 0x44000010,
108 
113 
115  0x00008000,
132 
133  IKP_UniqueIdMask = 0x0000ffff,
134  IKP_CustomDataBit = 0x00010000,
135 };
137 
138 // struct for storing and sorting solutions
140 {
141  std::vector<double> value;
143 
144  bool operator<(const LimitObeyingSol& a) const
145  {
146  return dist_from_seed < a.dist_from_seed;
147  }
148 };
149 
150 // Code generated by IKFast56/61
151 #include "_ROBOT_NAME___GROUP_NAME__ikfast_solver.cpp"
152 
154 {
155  std::vector<std::string> joint_names_;
156  std::vector<double> joint_min_vector_;
157  std::vector<double> joint_max_vector_;
158  std::vector<bool> joint_has_limits_vector_;
159  std::vector<std::string> link_names_;
160  const size_t num_joints_;
161  std::vector<int> free_params_;
162 
163  // The ikfast and base frame are the start and end of the kinematic chain for which the
164  // IKFast analytic solution was generated.
165  const std::string IKFAST_TIP_FRAME_ = "_EEF_LINK_";
166  const std::string IKFAST_BASE_FRAME_ = "_BASE_LINK_";
167 
168  // prefix added to tip- and baseframe to allow different namespaces or multi-robot setups
169  std::string link_prefix_;
170 
171  // The transform tip and base bool are set to true if this solver is used with a kinematic
172  // chain that extends beyond the ikfast tip and base frame. The solution will be valid so
173  // long as there are no active, passive, or mimic joints between either the ikfast_tip_frame
174  // and the tip_frame of the group or the ikfast_base_frame and the base_frame for the group.
177 
178  // We store the transform from the ikfast_base_frame to the group base_frame as well as the
179  // ikfast_tip_frame to the group tip_frame to transform input poses into the solver frame.
180  Eigen::Isometry3d chain_base_to_group_base_;
181  Eigen::Isometry3d group_tip_to_chain_tip_;
182 
183  bool initialized_; // Internal variable that indicates whether solvers are configured and ready
184  const std::string name_{ "ikfast" };
185 
186  const std::vector<std::string>& getJointNames() const override
187  {
188  return joint_names_;
189  }
190  const std::vector<std::string>& getLinkNames() const override
191  {
192  return link_names_;
193  }
194 
195 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
216  getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
217  std::vector<double>& solution, 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 = std::make_shared<RobotState>(robot_model_);
378  robot_state->setToDefaultValues();
379 
380  bool has_link; // to suppress ROS_ERRORs for non-existent frames
381  auto* from_link = robot_model_->getLinkModel(from, &has_link);
382  auto* to_link = robot_model_->getLinkModel(to, &has_link);
383  if (!from_link || !to_link)
384  return false;
385 
386  if (robot_model_->getRigidlyConnectedParentLinkModel(from_link) !=
387  robot_model_->getRigidlyConnectedParentLinkModel(to_link))
388  {
389  ROS_ERROR_STREAM_NAMED(name_, "Link frames " << from << " and " << to << " are not rigidly connected.");
390  return false;
391  }
392 
393  transform = robot_state->getGlobalLinkTransform(from_link).inverse() * robot_state->getGlobalLinkTransform(to_link);
394  differs_from_identity = !transform.matrix().isIdentity();
395  return true;
396 }
397 
398 bool IKFastKinematicsPlugin::initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name,
399  const std::string& base_frame, const std::vector<std::string>& tip_frames,
400  double search_discretization)
401 {
402  if (tip_frames.size() != 1)
403  {
404  ROS_ERROR_NAMED(name_, "Expecting exactly one tip frame.");
405  return false;
406  }
407 
408  storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
409  if (!lookupParam("link_prefix", link_prefix_, std::string("")))
410  {
411  ROS_INFO_NAMED(name_, "Using empty link_prefix.");
412  }
413  else
414  {
415  ROS_INFO_STREAM_NAMED(name_, "Using link_prefix: '" << link_prefix_ << "'");
416  }
417 
418  // verbose error output. subsequent checks in computeRelativeTransform return false then
419  if (!robot_model.hasLinkModel(tip_frames_[0]))
420  ROS_ERROR_STREAM_NAMED(name_, "tip frame '" << tip_frames_[0] << "' does not exist.");
421  if (!robot_model.hasLinkModel(base_frame_))
422  ROS_ERROR_STREAM_NAMED(name_, "base_frame '" << base_frame_ << "' does not exist.");
423 
424  if (!robot_model.hasLinkModel(link_prefix_ + IKFAST_TIP_FRAME_))
425  ROS_ERROR_STREAM_NAMED(name_, "prefixed tip frame '" << link_prefix_ + IKFAST_TIP_FRAME_
426  << "' does not exist. "
427  "Please check your link_prefix parameter.");
428  if (!robot_model.hasLinkModel(link_prefix_ + IKFAST_BASE_FRAME_))
429  ROS_ERROR_STREAM_NAMED(name_, "prefixed base frame '" << link_prefix_ + IKFAST_BASE_FRAME_
430  << "' does not exist. "
431  "Please check your link_prefix parameter.");
432  // This IKFast solution was generated with IKFAST_TIP_FRAME_ and IKFAST_BASE_FRAME_.
433  // It is often the case that fixed joints are added to these links to model things like
434  // a robot mounted on a table or a robot with an end effector attached to the last link.
435  // To support these use cases, we store the transform from the IKFAST_BASE_FRAME_ to the
436  // base_frame_ and IKFAST_TIP_FRAME_ the tip_frame_ and transform to the input pose accordingly
437  if (!computeRelativeTransform(tip_frames_[0], link_prefix_ + IKFAST_TIP_FRAME_, group_tip_to_chain_tip_,
438  tip_transform_required_) ||
439  !computeRelativeTransform(link_prefix_ + IKFAST_BASE_FRAME_, base_frame_, chain_base_to_group_base_,
440  base_transform_required_))
441  {
442  return false;
443  }
444 
445  // IKFast56/61
446  fillFreeParams(GetNumFreeParameters(), GetFreeParameters());
447 
448  if (free_params_.size() > 1)
449  {
450  ROS_ERROR_NAMED(name_, "Only one free joint parameter supported!");
451  return false;
452  }
453  else if (free_params_.size() == 1)
454  {
455  redundant_joint_indices_.clear();
456  redundant_joint_indices_.push_back(free_params_[0]);
457  KinematicsBase::setSearchDiscretization(search_discretization);
458  }
459 
460  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group_name);
461  if (!jmg)
462  {
463  ROS_ERROR_STREAM_NAMED(name_, "Unknown planning group: " << group_name);
464  return false;
465  }
466 
467  ROS_DEBUG_STREAM_NAMED(name_, "Registering joints and links");
468  const moveit::core::LinkModel* link = robot_model_->getLinkModel(tip_frames_[0]);
469  const moveit::core::LinkModel* base_link = robot_model_->getLinkModel(base_frame_);
470  while (link && link != base_link)
471  {
472  ROS_DEBUG_STREAM_NAMED(name_, "Link " << link->getName());
473  link_names_.push_back(link->getName());
474  const moveit::core::JointModel* joint = link->getParentJointModel();
475  if (joint->getType() != joint->UNKNOWN && joint->getType() != joint->FIXED && joint->getVariableCount() == 1)
476  {
477  ROS_DEBUG_STREAM_NAMED(name_, "Adding joint " << joint->getName());
478 
479  joint_names_.push_back(joint->getName());
480  const moveit::core::VariableBounds& bounds = joint->getVariableBounds()[0];
481  joint_has_limits_vector_.push_back(bounds.position_bounded_);
482  joint_min_vector_.push_back(bounds.min_position_);
483  joint_max_vector_.push_back(bounds.max_position_);
484  }
485  link = link->getParentLinkModel();
486  }
487 
488  if (joint_names_.size() != num_joints_)
489  {
490  ROS_FATAL_NAMED(name_, "Joint numbers of RobotModel (%zd) and IKFast solver (%zd) do not match",
491  joint_names_.size(), num_joints_);
492  return false;
493  }
494 
495  std::reverse(link_names_.begin(), link_names_.end());
496  std::reverse(joint_names_.begin(), joint_names_.end());
497  std::reverse(joint_min_vector_.begin(), joint_min_vector_.end());
498  std::reverse(joint_max_vector_.begin(), joint_max_vector_.end());
499  std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end());
500 
501  for (size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
502  ROS_DEBUG_STREAM_NAMED(name_, joint_names_[joint_id] << " " << joint_min_vector_[joint_id] << " "
503  << joint_max_vector_[joint_id] << " "
504  << joint_has_limits_vector_[joint_id]);
505 
506  initialized_ = true;
507  return true;
508 }
509 
510 void IKFastKinematicsPlugin::setSearchDiscretization(const std::map<unsigned int, double>& discretization)
511 {
512  if (discretization.empty())
513  {
514  ROS_ERROR("The 'discretization' map is empty");
515  return;
516  }
517 
518  if (redundant_joint_indices_.empty())
519  {
520  ROS_ERROR_STREAM_NAMED(name_, "This group's solver doesn't support redundant joints");
521  return;
522  }
523 
524  if (discretization.begin()->first != redundant_joint_indices_[0])
525  {
526  std::string redundant_joint = joint_names_[free_params_[0]];
527  ROS_ERROR_STREAM_NAMED(name_, "Attempted to discretize a non-redundant joint "
528  << discretization.begin()->first << ", only joint '" << redundant_joint
529  << "' with index " << redundant_joint_indices_[0] << " is redundant.");
530  return;
531  }
532 
533  if (discretization.begin()->second <= 0.0)
534  {
535  ROS_ERROR_STREAM_NAMED(name_, "Discretization can not takes values that are <= 0");
536  return;
537  }
538 
539  redundant_joint_discretization_.clear();
540  redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second;
541 }
542 
543 bool IKFastKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices)
544 {
545  ROS_ERROR_STREAM_NAMED(name_, "Changing the redundant joints isn't permitted by this group's solver ");
546  return false;
547 }
548 
549 size_t IKFastKinematicsPlugin::solve(KDL::Frame& pose_frame, const std::vector<double>& vfree,
550  IkSolutionList<IkReal>& solutions) const
551 {
552  // IKFast56/61
553  solutions.Clear();
554 
555  double trans[3];
556  trans[0] = pose_frame.p[0]; //-.18;
557  trans[1] = pose_frame.p[1];
558  trans[2] = pose_frame.p[2];
559 
560  KDL::Rotation mult;
561  KDL::Vector direction;
562 
563  IkParameterizationType ik_type = static_cast<IkParameterizationType>(GetIkType());
564 
565  switch (ik_type)
566  {
567  case IKP_Transform6D:
568  case IKP_Translation3D:
569  // For **Transform6D**, eerot is 9 values for the 3x3 rotation matrix. For **Translation3D**, these are ignored.
570 
571  mult = pose_frame.M;
572 
573  double vals[9];
574  vals[0] = mult(0, 0);
575  vals[1] = mult(0, 1);
576  vals[2] = mult(0, 2);
577  vals[3] = mult(1, 0);
578  vals[4] = mult(1, 1);
579  vals[5] = mult(1, 2);
580  vals[6] = mult(2, 0);
581  vals[7] = mult(2, 1);
582  vals[8] = mult(2, 2);
583 
584  // IKFast56/61
585  ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
586  return solutions.GetNumSolutions();
587 
588  case IKP_Direction3D:
589  case IKP_Ray4D:
591  // For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target
592  // direction.
593 
594  direction = pose_frame.M * KDL::Vector(_EEF_DIRECTION_);
595  // Making sure the resulting "direction" has a unit length, as users might pass in an unnormalized input through
596  // the input argument "--eef_direction"
597  direction.Normalize();
598  ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
599  return solutions.GetNumSolutions();
600 
602  // For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end
603  // effector coordinate system.
604  ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet.");
605  return 0;
606 
607  case IKP_TranslationXY2D:
608  ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
609  return solutions.GetNumSolutions();
610 
611  case IKP_Rotation3D:
612  case IKP_Lookat3D:
614  ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet.");
615  return 0;
616 
620  // For *TranslationXAxisAngle4D*, *TranslationYAxisAngle4D*, *TranslationZAxisAngle4D* - end effector origin
621  // reaches desired 3D translation; manipulator direction makes a specific angle with x/y/z-axis (defined in the
622  // manipulator base link's coordinate system)
626  // For **TranslationXAxisAngleZNorm4D**, **TranslationYAxisAngleXNorm4D**, **TranslationZAxisAngleYNorm4D** -
627  // end effector origin reaches desired 3D translation;
628  // manipulator direction needs to be orthogonal to z/x/y-axis and be rotated at a certain angle
629  // starting from the x/y/z-axis (defined in the manipulator base link’s coordinate system)
630  {
631  double angle = 0;
632  direction = pose_frame.M * KDL::Vector(_EEF_DIRECTION_);
633  // Making sure the resulting "direction" has a unit length, as users might pass in an unnormalized input through
634  // the input argument "--eef_direction"
635  direction.Normalize();
636 
637  switch (ik_type) // inner switch case
638  {
640  angle = std::acos(direction.x());
641  break;
643  angle = std::acos(direction.y());
644  break;
646  angle = std::acos(direction.z());
647  break;
649  angle = std::atan2(direction.y(), direction.x());
650  break;
652  angle = std::atan2(direction.z(), direction.y());
653  break;
655  angle = std::atan2(direction.x(), direction.z());
656  break;
657  default:
658  ROS_ERROR_STREAM_NAMED(name_, "An impossible case was reached with ik_type = " << ik_type);
659  return 0;
660  }
661 
662  ComputeIk(trans, &angle, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
663  return solutions.GetNumSolutions();
664  }
665 
666  default:
667  ROS_ERROR_NAMED(name_, "Unknown IkParameterizationType! "
668  "Was the solver generated with an incompatible version of Openrave?");
669  return 0;
670  }
671 }
672 
673 void IKFastKinematicsPlugin::getSolution(const IkSolutionList<IkReal>& solutions, int i,
674  std::vector<double>& solution) const
675 {
676  solution.clear();
677  solution.resize(num_joints_);
678 
679  // IKFast56/61
680  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
681  std::vector<IkReal> vsolfree(sol.GetFree().size());
682  sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : nullptr);
683 
684  for (std::size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
685  {
686  if (joint_has_limits_vector_[joint_id])
687  {
688  solution[joint_id] = enforceLimits(solution[joint_id], joint_min_vector_[joint_id], joint_max_vector_[joint_id]);
689  }
690  }
691 }
692 
693 void IKFastKinematicsPlugin::getSolution(const IkSolutionList<IkReal>& solutions,
694  const std::vector<double>& ik_seed_state, int i,
695  std::vector<double>& solution) const
696 {
697  solution.clear();
698  solution.resize(num_joints_);
699 
700  // IKFast56/61
701  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
702  std::vector<IkReal> vsolfree(sol.GetFree().size());
703  sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : nullptr);
704 
705  // rotate joints by +/-360° where it is possible and useful
706  for (std::size_t i = 0; i < num_joints_; ++i)
707  {
708  if (joint_has_limits_vector_[i])
709  {
710  solution[i] = enforceLimits(solution[i], joint_min_vector_[i], joint_max_vector_[i]);
711  double signed_distance = solution[i] - ik_seed_state[i];
712  while (signed_distance > M_PI && solution[i] - 2 * M_PI > (joint_min_vector_[i] - LIMIT_TOLERANCE))
713  {
714  signed_distance -= 2 * M_PI;
715  solution[i] -= 2 * M_PI;
716  }
717  while (signed_distance < -M_PI && solution[i] + 2 * M_PI < (joint_max_vector_[i] + LIMIT_TOLERANCE))
718  {
719  signed_distance += 2 * M_PI;
720  solution[i] += 2 * M_PI;
721  }
722  }
723  }
724 }
725 
726 double IKFastKinematicsPlugin::enforceLimits(double joint_value, double min, double max) const
727 {
728  // If the joint_value is greater than max subtract 2 * PI until it is less than the max
729  while (joint_value > max)
730  {
731  joint_value -= 2 * M_PI;
732  }
733 
734  // If the joint_value is less than the min, add 2 * PI until it is more than the min
735  while (joint_value < min)
736  {
737  joint_value += 2 * M_PI;
738  }
739  return joint_value;
740 }
741 
742 void IKFastKinematicsPlugin::fillFreeParams(int count, int* array)
743 {
744  free_params_.clear();
745  for (int i = 0; i < count; ++i)
746  free_params_.push_back(array[i]);
747 }
748 
749 bool IKFastKinematicsPlugin::getCount(int& count, const int& max_count, const int& min_count) const
750 {
751  if (count > 0)
752  {
753  if (-count >= min_count)
754  {
755  count = -count;
756  return true;
757  }
758  else if (count + 1 <= max_count)
759  {
760  count = count + 1;
761  return true;
762  }
763  else
764  {
765  return false;
766  }
767  }
768  else
769  {
770  if (1 - count <= max_count)
771  {
772  count = 1 - count;
773  return true;
774  }
775  else if (count - 1 >= min_count)
776  {
777  count = count - 1;
778  return true;
779  }
780  else
781  return false;
782  }
783 }
784 
785 bool IKFastKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
786  const std::vector<double>& joint_angles,
787  std::vector<geometry_msgs::Pose>& poses) const
788 {
789  if (GetIkType() != IKP_Transform6D)
790  {
791  // ComputeFk() is the inverse function of ComputeIk(), so the format of
792  // eerot differs depending on IK type. The Transform6D IK type is the only
793  // one for which a 3x3 rotation matrix is returned, which means we can only
794  // compute FK for that IK type.
795  ROS_ERROR_NAMED(name_, "Can only compute FK for Transform6D IK type!");
796  return false;
797  }
798 
799  KDL::Frame p_out;
800  if (link_names.size() == 0)
801  {
802  ROS_WARN_STREAM_NAMED(name_, "Link names with nothing");
803  return false;
804  }
805 
806  if (link_names.size() != 1 || link_names[0] != getTipFrame())
807  {
808  ROS_ERROR_NAMED(name_, "Can compute FK for %s only", getTipFrame().c_str());
809  return false;
810  }
811 
812  bool valid = true;
813 
814  IkReal eerot[9], eetrans[3];
815 
816  if (joint_angles.size() != num_joints_)
817  {
818  ROS_ERROR_NAMED(name_, "Unexpected number of joint angles");
819  return false;
820  }
821 
822  IkReal angles[num_joints_];
823  for (unsigned char i = 0; i < num_joints_; i++)
824  angles[i] = joint_angles[i];
825 
826  // IKFast56/61
827  ComputeFk(angles, eetrans, eerot);
828 
829  for (int i = 0; i < 3; ++i)
830  p_out.p.data[i] = eetrans[i];
831 
832  for (int i = 0; i < 9; ++i)
833  p_out.M.data[i] = eerot[i];
834 
835  poses.resize(1);
836  poses[0] = tf2::toMsg(p_out);
837 
838  return valid;
839 }
840 
841 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
842  const std::vector<double>& ik_seed_state, double timeout,
843  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
844  const kinematics::KinematicsQueryOptions& options) const
845 {
846  std::vector<double> consistency_limits;
847  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
848  options);
849 }
850 
851 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
852  const std::vector<double>& ik_seed_state, double timeout,
853  const std::vector<double>& consistency_limits,
854  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
855  const kinematics::KinematicsQueryOptions& options) const
856 {
857  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), 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  std::vector<double>& solution, const IKCallbackFn& solution_callback,
864  moveit_msgs::MoveItErrorCodes& error_code,
865  const kinematics::KinematicsQueryOptions& options) const
866 {
867  std::vector<double> consistency_limits;
868  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
869  options);
870 }
871 
872 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
873  const std::vector<double>& ik_seed_state, double timeout,
874  const std::vector<double>& consistency_limits,
875  std::vector<double>& solution, const IKCallbackFn& solution_callback,
876  moveit_msgs::MoveItErrorCodes& error_code,
877  const kinematics::KinematicsQueryOptions& options) const
878 {
879  // "SEARCH_MODE" is fixed during code generation
880  SEARCH_MODE search_mode = _SEARCH_MODE_;
881 
882  // Check if there are no redundant joints
883  if (free_params_.size() == 0)
884  {
885  ROS_DEBUG_STREAM_NAMED(name_, "No need to search since no free params/redundant joints");
886 
887  std::vector<geometry_msgs::Pose> ik_poses(1, ik_pose);
888  std::vector<std::vector<double>> solutions;
889  kinematics::KinematicsResult kinematic_result;
890  // Find all IK solutions within joint limits
891  if (!getPositionIK(ik_poses, ik_seed_state, solutions, kinematic_result, options))
892  {
893  ROS_DEBUG_STREAM_NAMED(name_, "No solution whatsoever");
894  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
895  return false;
896  }
897 
898  // sort solutions by their distance to the seed
899  std::vector<LimitObeyingSol> solutions_obey_limits;
900  for (std::size_t i = 0; i < solutions.size(); ++i)
901  {
902  double dist_from_seed = 0.0;
903  for (std::size_t j = 0; j < ik_seed_state.size(); ++j)
904  {
905  dist_from_seed += fabs(ik_seed_state[j] - solutions[i][j]);
906  }
907 
908  solutions_obey_limits.push_back({ solutions[i], dist_from_seed });
909  }
910  std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
911 
912  // check for collisions if a callback is provided
913  if (!solution_callback.empty())
914  {
915  for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i)
916  {
917  solution_callback(ik_pose, solutions_obey_limits[i].value, error_code);
918  if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
919  {
920  solution = solutions_obey_limits[i].value;
921  ROS_DEBUG_STREAM_NAMED(name_, "Solution passes callback");
922  return true;
923  }
924  }
925 
926  ROS_DEBUG_STREAM_NAMED(name_, "Solution has error code " << error_code);
927  return false;
928  }
929  else
930  {
931  solution = solutions_obey_limits[0].value;
932  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
933  return true; // no collision check callback provided
934  }
935  }
936 
937  // -------------------------------------------------------------------------------------------------
938  // Error Checking
939  if (!initialized_)
940  {
941  ROS_ERROR_STREAM_NAMED(name_, "Kinematics not active");
942  error_code.val = error_code.NO_IK_SOLUTION;
943  return false;
944  }
945 
946  if (ik_seed_state.size() != num_joints_)
947  {
949  "Seed state must have size " << num_joints_ << " instead of size " << ik_seed_state.size());
950  error_code.val = error_code.NO_IK_SOLUTION;
951  return false;
952  }
953 
954  if (!consistency_limits.empty() && consistency_limits.size() != num_joints_)
955  {
956  ROS_ERROR_STREAM_NAMED(name_, "Consistency limits be empty or must have size " << num_joints_ << " instead of size "
957  << consistency_limits.size());
958  error_code.val = error_code.NO_IK_SOLUTION;
959  return false;
960  }
961 
962  // -------------------------------------------------------------------------------------------------
963  // Initialize
964 
965  KDL::Frame frame;
966  transformToChainFrame(ik_pose, frame);
967 
968  std::vector<double> vfree(free_params_.size());
969 
970  int counter = 0;
971 
972  double initial_guess = ik_seed_state[free_params_[0]];
973  vfree[0] = initial_guess;
974 
975  // -------------------------------------------------------------------------------------------------
976  // Handle consitency limits if needed
977  int num_positive_increments;
978  int num_negative_increments;
979  double search_discretization = redundant_joint_discretization_.at(free_params_[0]);
980 
981  if (!consistency_limits.empty())
982  {
983  // MoveIt replaced consistency_limit (scalar) w/ consistency_limits (vector)
984  // Assume [0]th free_params element for now. Probably wrong.
985  double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess + consistency_limits[free_params_[0]]);
986  double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess - consistency_limits[free_params_[0]]);
987 
988  num_positive_increments = static_cast<int>((max_limit - initial_guess) / search_discretization);
989  num_negative_increments = static_cast<int>((initial_guess - min_limit) / search_discretization);
990  }
991  else // no consistency limits provided
992  {
993  num_positive_increments = (joint_max_vector_[free_params_[0]] - initial_guess) / search_discretization;
994  num_negative_increments = (initial_guess - joint_min_vector_[free_params_[0]]) / search_discretization;
995  }
996 
997  // -------------------------------------------------------------------------------------------------
998  // Begin searching
999 
1000  ROS_DEBUG_STREAM_NAMED(name_, "Free param is " << free_params_[0] << " initial guess is " << initial_guess
1001  << ", # positive increments: " << num_positive_increments
1002  << ", # negative increments: " << num_negative_increments);
1003  if ((search_mode & OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000)
1004  ROS_WARN_STREAM_ONCE_NAMED(name_, "Large search space, consider increasing the search discretization");
1005 
1006  double best_costs = -1.0;
1007  std::vector<double> best_solution;
1008  int nattempts = 0, nvalid = 0;
1009 
1010  while (true)
1011  {
1012  IkSolutionList<IkReal> solutions;
1013  size_t numsol = solve(frame, vfree, solutions);
1014 
1015  ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast");
1016 
1017  if (numsol > 0)
1018  {
1019  for (size_t s = 0; s < numsol; ++s)
1020  {
1021  nattempts++;
1022  std::vector<double> sol;
1023  getSolution(solutions, ik_seed_state, s, sol);
1024 
1025  bool obeys_limits = true;
1026  for (size_t i = 0; i < sol.size(); i++)
1027  {
1028  if (joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
1029  {
1030  obeys_limits = false;
1031  break;
1032  }
1033  // ROS_INFO_STREAM_NAMED(name_,"Num " << i << " value " << sol[i] << " has limits " <<
1034  // joint_has_limits_vector_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i]);
1035  }
1036  if (obeys_limits)
1037  {
1038  getSolution(solutions, ik_seed_state, s, solution);
1039 
1040  // This solution is within joint limits, now check if in collision (if callback provided)
1041  if (!solution_callback.empty())
1042  {
1043  solution_callback(ik_pose, solution, error_code);
1044  }
1045  else
1046  {
1047  error_code.val = error_code.SUCCESS;
1048  }
1049 
1050  if (error_code.val == error_code.SUCCESS)
1051  {
1052  nvalid++;
1053  if (search_mode & OPTIMIZE_MAX_JOINT)
1054  {
1055  // Costs for solution: Largest joint motion
1056  double costs = 0.0;
1057  for (unsigned int i = 0; i < solution.size(); i++)
1058  {
1059  double d = fabs(ik_seed_state[i] - solution[i]);
1060  if (d > costs)
1061  costs = d;
1062  }
1063  if (costs < best_costs || best_costs == -1.0)
1064  {
1065  best_costs = costs;
1066  best_solution = solution;
1067  }
1068  }
1069  else
1070  // Return first feasible solution
1071  return true;
1072  }
1073  }
1074  }
1075  }
1076 
1077  if (!getCount(counter, num_positive_increments, -num_negative_increments))
1078  {
1079  // Everything searched
1080  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1081  break;
1082  }
1083 
1084  vfree[0] = initial_guess + search_discretization * counter;
1085  // ROS_DEBUG_STREAM_NAMED(name_,"Attempt " << counter << " with 0th free joint having value " << vfree[0]);
1086  }
1087 
1088  ROS_DEBUG_STREAM_NAMED(name_, "Valid solutions: " << nvalid << "/" << nattempts);
1089 
1090  if ((search_mode & OPTIMIZE_MAX_JOINT) && best_costs != -1.0)
1091  {
1092  solution = best_solution;
1093  error_code.val = error_code.SUCCESS;
1094  return true;
1095  }
1096 
1097  // No solution found
1098  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1099  return false;
1100 }
1101 
1102 // Used when there are no redundant joints - aka no free params
1103 bool IKFastKinematicsPlugin::getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
1104  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
1105  const kinematics::KinematicsQueryOptions& options) const
1106 {
1107  ROS_DEBUG_STREAM_NAMED(name_, "getPositionIK");
1108 
1109  if (!initialized_)
1110  {
1111  ROS_ERROR_NAMED(name_, "kinematics not active");
1112  return false;
1113  }
1114 
1115  if (ik_seed_state.size() < num_joints_)
1116  {
1117  ROS_ERROR_STREAM_NAMED(name_, "ik_seed_state only has " << ik_seed_state.size()
1118  << " entries, this ikfast solver requires " << num_joints_);
1119  return false;
1120  }
1121 
1122  // Check if seed is in bound
1123  for (std::size_t i = 0; i < ik_seed_state.size(); i++)
1124  {
1125  // Add tolerance to limit check
1126  if (joint_has_limits_vector_[i] && ((ik_seed_state[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1127  (ik_seed_state[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1128  {
1129  ROS_DEBUG_STREAM_NAMED(name_, "IK seed not in limits! " << static_cast<int>(i) << " value " << ik_seed_state[i]
1130  << " has limit: " << joint_has_limits_vector_[i]
1131  << " being " << joint_min_vector_[i] << " to "
1132  << joint_max_vector_[i]);
1133  return false;
1134  }
1135  }
1136 
1137  std::vector<double> vfree(free_params_.size());
1138  for (std::size_t i = 0; i < free_params_.size(); ++i)
1139  {
1140  int p = free_params_[i];
1141  ROS_ERROR("%u is %f", p, ik_seed_state[p]); // DTC
1142  vfree[i] = ik_seed_state[p];
1143  }
1144 
1145  KDL::Frame frame;
1146  transformToChainFrame(ik_pose, frame);
1147 
1148  IkSolutionList<IkReal> solutions;
1149  size_t numsol = solve(frame, vfree, solutions);
1150  ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast");
1151 
1152  std::vector<LimitObeyingSol> solutions_obey_limits;
1153 
1154  if (numsol)
1155  {
1156  std::vector<double> solution_obey_limits;
1157  for (std::size_t s = 0; s < numsol; ++s)
1158  {
1159  std::vector<double> sol;
1160  getSolution(solutions, ik_seed_state, s, sol);
1161  ROS_DEBUG_NAMED(name_, "Sol %d: %e %e %e %e %e %e", static_cast<int>(s), sol[0], sol[1], sol[2], sol[3],
1162  sol[4], sol[5]);
1163 
1164  bool obeys_limits = true;
1165  for (std::size_t i = 0; i < sol.size(); i++)
1166  {
1167  // Add tolerance to limit check
1168  if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1169  (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1170  {
1171  // One element of solution is not within limits
1172  obeys_limits = false;
1173  ROS_DEBUG_STREAM_NAMED(name_, "Not in limits! " << static_cast<int>(i) << " value " << sol[i]
1174  << " has limit: " << joint_has_limits_vector_[i]
1175  << " being " << joint_min_vector_[i] << " to "
1176  << joint_max_vector_[i]);
1177  break;
1178  }
1179  }
1180  if (obeys_limits)
1181  {
1182  // All elements of this solution obey limits
1183  getSolution(solutions, ik_seed_state, s, solution_obey_limits);
1184  double dist_from_seed = 0.0;
1185  for (std::size_t i = 0; i < ik_seed_state.size(); ++i)
1186  {
1187  dist_from_seed += fabs(ik_seed_state[i] - solution_obey_limits[i]);
1188  }
1189 
1190  solutions_obey_limits.push_back({ solution_obey_limits, dist_from_seed });
1191  }
1192  }
1193  }
1194  else
1195  {
1196  ROS_DEBUG_STREAM_NAMED(name_, "No IK solution");
1197  }
1198 
1199  // Sort the solutions under limits and find the one that is closest to ik_seed_state
1200  if (!solutions_obey_limits.empty())
1201  {
1202  std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
1203  solution = solutions_obey_limits[0].value;
1204  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
1205  return true;
1206  }
1207 
1208  error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1209  return false;
1210 }
1211 
1212 bool IKFastKinematicsPlugin::getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses,
1213  const std::vector<double>& ik_seed_state,
1214  std::vector<std::vector<double>>& solutions,
1216  const kinematics::KinematicsQueryOptions& options) const
1217 {
1218  ROS_DEBUG_STREAM_NAMED(name_, "getPositionIK with multiple solutions");
1219 
1220  if (!initialized_)
1221  {
1222  ROS_ERROR_NAMED(name_, "kinematics not active");
1224  return false;
1225  }
1226 
1227  if (ik_poses.empty())
1228  {
1229  ROS_ERROR_NAMED(name_, "ik_poses is empty");
1231  return false;
1232  }
1233 
1234  if (ik_poses.size() > 1)
1235  {
1236  ROS_ERROR_NAMED(name_, "ik_poses contains multiple entries, only one is allowed");
1238  return false;
1239  }
1240 
1241  if (ik_seed_state.size() < num_joints_)
1242  {
1243  ROS_ERROR_STREAM_NAMED(name_, "ik_seed_state only has " << ik_seed_state.size()
1244  << " entries, this ikfast solver requires " << num_joints_);
1245  return false;
1246  }
1247 
1248  KDL::Frame frame;
1249  transformToChainFrame(ik_poses[0], frame);
1250 
1251  // solving ik
1252  std::vector<IkSolutionList<IkReal>> solution_set;
1253  IkSolutionList<IkReal> ik_solutions;
1254  std::vector<double> vfree;
1255  int numsol = 0;
1256  std::vector<double> sampled_joint_vals;
1257  if (!redundant_joint_indices_.empty())
1258  {
1259  // initializing from seed
1260  sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]);
1261 
1262  // checking joint limits when using no discretization
1264  joint_has_limits_vector_[redundant_joint_indices_.front()])
1265  {
1266  double joint_min = joint_min_vector_[redundant_joint_indices_.front()];
1267  double joint_max = joint_max_vector_[redundant_joint_indices_.front()];
1268 
1269  double jv = sampled_joint_vals[0];
1270  if (!((jv > (joint_min - LIMIT_TOLERANCE)) && (jv < (joint_max + LIMIT_TOLERANCE))))
1271  {
1273  ROS_ERROR_STREAM_NAMED(name_, "ik seed is out of bounds");
1274  return false;
1275  }
1276  }
1277 
1278  // computing all solutions sets for each sampled value of the redundant joint
1279  if (!sampleRedundantJoint(options.discretization_method, sampled_joint_vals))
1280  {
1282  return false;
1283  }
1284 
1285  for (unsigned int i = 0; i < sampled_joint_vals.size(); i++)
1286  {
1287  vfree.clear();
1288  vfree.push_back(sampled_joint_vals[i]);
1289  numsol += solve(frame, vfree, ik_solutions);
1290  solution_set.push_back(ik_solutions);
1291  }
1292  }
1293  else
1294  {
1295  // computing for single solution set
1296  numsol = solve(frame, vfree, ik_solutions);
1297  solution_set.push_back(ik_solutions);
1298  }
1299 
1300  ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast");
1301  bool solutions_found = false;
1302  if (numsol > 0)
1303  {
1304  /*
1305  Iterating through all solution sets and storing those that do not exceed joint limits.
1306  */
1307  for (unsigned int r = 0; r < solution_set.size(); r++)
1308  {
1309  ik_solutions = solution_set[r];
1310  numsol = ik_solutions.GetNumSolutions();
1311  for (int s = 0; s < numsol; ++s)
1312  {
1313  std::vector<double> sol;
1314  getSolution(ik_solutions, ik_seed_state, s, sol);
1315 
1316  bool obeys_limits = true;
1317  for (unsigned int i = 0; i < sol.size(); i++)
1318  {
1319  // Add tolerance to limit check
1320  if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1321  (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1322  {
1323  // One element of solution is not within limits
1324  obeys_limits = false;
1325  ROS_DEBUG_STREAM_NAMED(name_, "Not in limits! " << i << " value " << sol[i] << " has limit: "
1326  << joint_has_limits_vector_[i] << " being "
1327  << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
1328  break;
1329  }
1330  }
1331  if (obeys_limits)
1332  {
1333  // All elements of solution obey limits
1334  solutions_found = true;
1335  solutions.push_back(sol);
1336  }
1337  }
1338  }
1339 
1340  if (solutions_found)
1341  {
1343  return true;
1344  }
1345  }
1346  else
1347  {
1348  ROS_DEBUG_STREAM_NAMED(name_, "No IK solution");
1349  }
1350 
1352  return false;
1353 }
1354 
1355 bool IKFastKinematicsPlugin::sampleRedundantJoint(kinematics::DiscretizationMethod method,
1356  std::vector<double>& sampled_joint_vals) const
1357 {
1358  int index = redundant_joint_indices_.front();
1359  double joint_dscrt = redundant_joint_discretization_.at(index);
1360  double joint_min = joint_min_vector_[index];
1361  double joint_max = joint_max_vector_[index];
1362 
1363  switch (method)
1364  {
1366  {
1367  size_t steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1368  for (size_t i = 0; i < steps; i++)
1369  {
1370  sampled_joint_vals.push_back(joint_min + joint_dscrt * i);
1371  }
1372  sampled_joint_vals.push_back(joint_max);
1373  }
1374  break;
1376  {
1377  int steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1378  steps = steps > 0 ? steps : 1;
1379  double diff = joint_max - joint_min;
1380  for (int i = 0; i < steps; i++)
1381  {
1382  sampled_joint_vals.push_back(((diff * std::rand()) / (static_cast<double>(RAND_MAX))) + joint_min);
1383  }
1384  }
1385 
1386  break;
1388 
1389  break;
1390  default:
1391  ROS_ERROR_STREAM_NAMED(name_, "Discretization method " << method << " is not supported");
1392  return false;
1393  }
1394 
1395  return true;
1396 }
1397 
1398 void IKFastKinematicsPlugin::transformToChainFrame(const geometry_msgs::Pose& ik_pose, KDL::Frame& ik_pose_chain) const
1399 {
1400  if (tip_transform_required_ || base_transform_required_)
1401  {
1402  Eigen::Isometry3d ik_eigen_pose;
1403  tf2::fromMsg(ik_pose, ik_eigen_pose);
1404  if (tip_transform_required_)
1405  ik_eigen_pose = ik_eigen_pose * group_tip_to_chain_tip_;
1406 
1407  if (base_transform_required_)
1408  ik_eigen_pose = chain_base_to_group_base_ * ik_eigen_pose;
1409 
1410  tf2::fromMsg(tf2::toMsg(ik_eigen_pose), ik_pose_chain);
1411  }
1412  else
1413  {
1414  tf2::fromMsg(ik_pose, ik_pose_chain);
1415  }
1416 }
1417 
1418 } // namespace _NAMESPACE_
1419 
1420 // register IKFastKinematicsPlugin as a KinematicsBase implementation
SEARCH_MODE
SEARCH_MODE
Search modes for searchPositionIK(), see there.
Definition: ikfast61_moveit_plugin_template.cpp:56
moveit::core::LinkModel
moveit::core
_NAMESPACE_::IKP_TranslationYAxisAngle4DVelocity
@ IKP_TranslationYAxisAngle4DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:127
_NAMESPACE_::IKP_TranslationZAxisAngleYNorm4DVelocity
@ IKP_TranslationZAxisAngleYNorm4DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:131
_NAMESPACE_::IKFastKinematicsPlugin::link_names_
std::vector< std::string > link_names_
Definition: ikfast61_moveit_plugin_template.cpp:159
initialize
bool initialize(MeshCollisionTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, bool use_refit, bool refit_bottomup)
_NAMESPACE_::IKP_TranslationLocalGlobal6D
@ IKP_TranslationLocalGlobal6D
local point on end effector origin reaches desired 3D global point
Definition: ikfast61_moveit_plugin_template.cpp:87
_NAMESPACE_::IKP_Lookat3DVelocity
@ IKP_Lookat3DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:121
moveit::core::JointModel::getVariableCount
std::size_t getVariableCount() const
_NAMESPACE_::IKP_TranslationZAxisAngleYNorm4D
@ IKP_TranslationZAxisAngleYNorm4D
Definition: ikfast61_moveit_plugin_template.cpp:107
_NAMESPACE_::IKFastKinematicsPlugin::base_transform_required_
bool base_transform_required_
Definition: ikfast61_moveit_plugin_template.cpp:176
_NAMESPACE_::IKP_TranslationZAxisAngle4D
@ IKP_TranslationZAxisAngle4D
Definition: ikfast61_moveit_plugin_template.cpp:95
angles
_NAMESPACE_::IKFastKinematicsPlugin::tip_transform_required_
bool tip_transform_required_
Definition: ikfast61_moveit_plugin_template.cpp:175
moveit::core::VariableBounds
_NAMESPACE_::IKP_Direction3DVelocity
@ IKP_Direction3DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:119
moveit::core::VariableBounds::max_position_
double max_position_
_NAMESPACE_::IKP_CustomDataBit
@ IKP_CustomDataBit
Definition: ikfast61_moveit_plugin_template.cpp:134
tf2_eigen.h
tf2::fromMsg
void fromMsg(const A &, B &b)
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
s
XmlRpcServer s
_NAMESPACE_::IKFastKinematicsPlugin::link_prefix_
std::string link_prefix_
Definition: ikfast61_moveit_plugin_template.cpp:169
ros.h
_NAMESPACE_::LimitObeyingSol
Definition: ikfast61_moveit_plugin_template.cpp:139
_NAMESPACE_::IKFastKinematicsPlugin
Definition: ikfast61_moveit_plugin_template.cpp:153
moveit::core::RobotModel
_NAMESPACE_::IKFastKinematicsPlugin::joint_has_limits_vector_
std::vector< bool > joint_has_limits_vector_
Definition: ikfast61_moveit_plugin_template.cpp:158
kinematics::KinematicErrors::MULTIPLE_TIPS_NOT_SUPPORTED
MULTIPLE_TIPS_NOT_SUPPORTED
moveit::core::JointModel::getName
const std::string & getName() const
kinematics::DiscretizationMethods::ALL_RANDOM_SAMPLED
ALL_RANDOM_SAMPLED
_NAMESPACE_::IKP_VelocityDataBit
@ IKP_VelocityDataBit
bit is set if the data represents the time-derivate velocity of an IkParameterization
Definition: ikfast61_moveit_plugin_template.cpp:114
_NAMESPACE_::IKP_TranslationXAxisAngle4D
@ IKP_TranslationXAxisAngle4D
Definition: ikfast61_moveit_plugin_template.cpp:89
moveit::core::LinkModel::getParentJointModel
const JointModel * getParentJointModel() const
_NAMESPACE_::IkParameterizationType
IkParameterizationType
The types of inverse kinematics parameterizations supported.
Definition: ikfast61_moveit_plugin_template.cpp:71
_NAMESPACE_::IKP_TranslationYAxisAngle4D
@ IKP_TranslationYAxisAngle4D
Definition: ikfast61_moveit_plugin_template.cpp:92
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
_NAMESPACE_::IKP_TranslationDirection5D
@ IKP_TranslationDirection5D
Definition: ikfast61_moveit_plugin_template.cpp:80
moveit::core::VariableBounds::min_position_
double min_position_
robot_state.h
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
_NAMESPACE_::IKP_TranslationXY2DVelocity
@ IKP_TranslationXY2DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:123
kinematics::KinematicsBase::IKCallbackFn
boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)> IKCallbackFn
ROS_FATAL_NAMED
#define ROS_FATAL_NAMED(name,...)
kinematics::KinematicErrors::UNSUPORTED_DISCRETIZATION_REQUESTED
UNSUPORTED_DISCRETIZATION_REQUESTED
_NAMESPACE_::IKP_Translation3DVelocity
@ IKP_Translation3DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:118
_NAMESPACE_::IKP_TranslationXY2D
@ IKP_TranslationXY2D
2D translation along XY plane
Definition: ikfast61_moveit_plugin_template.cpp:83
moveit::core::JointModel::getType
JointType getType() const
_NAMESPACE_::IKFastKinematicsPlugin::joint_min_vector_
std::vector< double > joint_min_vector_
Definition: ikfast61_moveit_plugin_template.cpp:156
_NAMESPACE_::IKP_Rotation3DVelocity
@ IKP_Rotation3DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:117
_NAMESPACE_::IKP_TranslationXAxisAngleZNorm4D
@ IKP_TranslationXAxisAngleZNorm4D
Definition: ikfast61_moveit_plugin_template.cpp:99
kinematics::KinematicErrors::OK
OK
_NAMESPACE_::IKP_Rotation3D
@ IKP_Rotation3D
end effector reaches desired 3D rotation
Definition: ikfast61_moveit_plugin_template.cpp:75
OPTIMIZE_FREE_JOINT
@ OPTIMIZE_FREE_JOINT
Definition: ikfast61_moveit_plugin_template.cpp:58
_NAMESPACE_::IKFastKinematicsPlugin::chain_base_to_group_base_
Eigen::Isometry3d chain_base_to_group_base_
Definition: ikfast61_moveit_plugin_template.cpp:180
kinematics::DiscretizationMethods::DiscretizationMethod
DiscretizationMethod
_NAMESPACE_::IKFastKinematicsPlugin::num_joints_
const size_t num_joints_
Definition: ikfast61_moveit_plugin_template.cpp:160
moveit::core::JointModel::getVariableBounds
const VariableBounds & getVariableBounds(const std::string &variable) const
_NAMESPACE_::IKFastKinematicsPlugin::joint_max_vector_
std::vector< double > joint_max_vector_
Definition: ikfast61_moveit_plugin_template.cpp:157
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
_NAMESPACE_::IKFastKinematicsPlugin::IKFastKinematicsPlugin
IKFastKinematicsPlugin()
Interface for an IKFast kinematics plugin.
Definition: ikfast61_moveit_plugin_template.cpp:197
_NAMESPACE_::IKP_Direction3D
@ IKP_Direction3D
direction on end effector coordinate system reaches desired direction
Definition: ikfast61_moveit_plugin_template.cpp:77
kinematics::KinematicsBase
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
_NAMESPACE_::IKP_TranslationXYOrientation3DVelocity
@ IKP_TranslationXYOrientation3DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:124
_NAMESPACE_
Definition: ikfast61_moveit_plugin_template.cpp:62
ROS_ERROR
#define ROS_ERROR(...)
kinematics::KinematicErrors::IK_SEED_OUTSIDE_LIMITS
IK_SEED_OUTSIDE_LIMITS
tf2_kdl.h
d
d
LIMIT_TOLERANCE
const double LIMIT_TOLERANCE
Definition: ikfast61_moveit_plugin_template.cpp:54
moveit::core::JointModel::UNKNOWN
UNKNOWN
_NAMESPACE_::IKP_TranslationXAxisAngleZNorm4DVelocity
@ IKP_TranslationXAxisAngleZNorm4DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:129
kinematics::KinematicsResult
ROS_WARN_STREAM_ONCE_NAMED
#define ROS_WARN_STREAM_ONCE_NAMED(name, args)
r
S r
kinematics::KinematicsQueryOptions::discretization_method
DiscretizationMethod discretization_method
ROS_WARN_STREAM_NAMED
#define ROS_WARN_STREAM_NAMED(name, args)
_NAMESPACE_::IKP_Translation3D
@ IKP_Translation3D
end effector origin reaches desired 3D translation
Definition: ikfast61_moveit_plugin_template.cpp:76
kinematics::KinematicErrors::EMPTY_TIP_POSES
EMPTY_TIP_POSES
_NAMESPACE_::IKP_Transform6DVelocity
@ IKP_Transform6DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:116
kinematics::DiscretizationMethods::NO_DISCRETIZATION
NO_DISCRETIZATION
_NAMESPACE_::LimitObeyingSol::value
std::vector< double > value
Definition: ikfast61_moveit_plugin_template.cpp:141
_NAMESPACE_::IKFastKinematicsPlugin::initialized_
bool initialized_
Definition: ikfast61_moveit_plugin_template.cpp:183
kinematics::KinematicsQueryOptions
_NAMESPACE_::IKFastKinematicsPlugin::free_params_
std::vector< int > free_params_
Definition: ikfast61_moveit_plugin_template.cpp:161
M_PI
#define M_PI
_NAMESPACE_::IKP_Transform6D
@ IKP_Transform6D
end effector reaches desired 6D transformation
Definition: ikfast61_moveit_plugin_template.cpp:74
class_list_macros.hpp
kinematics_base.h
_NAMESPACE_::IKP_TranslationYAxisAngleXNorm4D
@ IKP_TranslationYAxisAngleXNorm4D
Definition: ikfast61_moveit_plugin_template.cpp:103
moveit::core::JointModelGroup
_NAMESPACE_::IKFastKinematicsPlugin::group_tip_to_chain_tip_
Eigen::Isometry3d group_tip_to_chain_tip_
Definition: ikfast61_moveit_plugin_template.cpp:181
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(_NAMESPACE_::IKFastKinematicsPlugin, kinematics::KinematicsBase)
angle
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
index
unsigned int index
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
_NAMESPACE_::IKP_TranslationYAxisAngleXNorm4DVelocity
@ IKP_TranslationYAxisAngleXNorm4DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:130
tf2::toMsg
B toMsg(const A &a)
_NAMESPACE_::IKP_TranslationXYOrientation3D
@ IKP_TranslationXYOrientation3D
Definition: ikfast61_moveit_plugin_template.cpp:84
_NAMESPACE_::IKP_TranslationZAxisAngle4DVelocity
@ IKP_TranslationZAxisAngle4DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:128
kinematics::KinematicErrors::NO_SOLUTION
NO_SOLUTION
_NAMESPACE_::LimitObeyingSol::dist_from_seed
double dist_from_seed
Definition: ikfast61_moveit_plugin_template.cpp:142
_NAMESPACE_::IKP_None
@ IKP_None
Definition: ikfast61_moveit_plugin_template.cpp:73
OPTIMIZE_MAX_JOINT
@ OPTIMIZE_MAX_JOINT
Definition: ikfast61_moveit_plugin_template.cpp:59
_NAMESPACE_::IKP_Lookat3D
@ IKP_Lookat3D
direction on end effector coordinate system points to desired 3D position
Definition: ikfast61_moveit_plugin_template.cpp:79
_NAMESPACE_::IKP_NumberOfParameterizations
@ IKP_NumberOfParameterizations
number of parameterizations (does not count IKP_None)
Definition: ikfast61_moveit_plugin_template.cpp:112
_NAMESPACE_::IKP_TranslationDirection5DVelocity
@ IKP_TranslationDirection5DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:122
_NAMESPACE_::IKP_TranslationXAxisAngle4DVelocity
@ IKP_TranslationXAxisAngle4DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:126
_NAMESPACE_::IKFastKinematicsPlugin::getLinkNames
const std::vector< std::string > & getLinkNames() const override
Definition: ikfast61_moveit_plugin_template.cpp:190
_NAMESPACE_::IKFastKinematicsPlugin::joint_names_
std::vector< std::string > joint_names_
Definition: ikfast61_moveit_plugin_template.cpp:155
moveit::core::VariableBounds::position_bounded_
bool position_bounded_
moveit::core::LinkModel::getName
const std::string & getName() const
_NAMESPACE_::IKFastKinematicsPlugin::getJointNames
const std::vector< std::string > & getJointNames() const override
Definition: ikfast61_moveit_plugin_template.cpp:186
kinematics::KinematicsResult::kinematic_error
KinematicError kinematic_error
_NAMESPACE_::IKP_TranslationLocalGlobal6DVelocity
@ IKP_TranslationLocalGlobal6DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:125
_NAMESPACE_::IKP_Ray4D
@ IKP_Ray4D
ray on end effector coordinate system reaches desired global ray
Definition: ikfast61_moveit_plugin_template.cpp:78
moveit::core::JointModel::FIXED
FIXED
_NAMESPACE_::IKP_UniqueIdMask
@ IKP_UniqueIdMask
the mask for the unique ids
Definition: ikfast61_moveit_plugin_template.cpp:133
_NAMESPACE_::IKP_Ray4DVelocity
@ IKP_Ray4DVelocity
Definition: ikfast61_moveit_plugin_template.cpp:120
moveit::core::JointModel
kinematics::KinematicErrors::SOLVER_NOT_ACTIVE
SOLVER_NOT_ACTIVE
moveit::core::RobotModel::hasLinkModel
bool hasLinkModel(const std::string &name) const
moveit::core::LinkModel::getParentLinkModel
const LinkModel * getParentLinkModel() const
kinematics::DiscretizationMethods::ALL_DISCRETIZED
ALL_DISCRETIZED
_NAMESPACE_::LimitObeyingSol::operator<
bool operator<(const LimitObeyingSol &a) const
Definition: ikfast61_moveit_plugin_template.cpp:144


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Fri May 3 2024 02:29:33