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