moveit2
The MoveIt Motion Planning Framework for ROS 2.
prbt_manipulator_ikfast_moveit_plugin.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Dave Coleman, CU Boulder; Jeremy Zoss, SwRI; David Butterworth, KAIST; Mathias Lüdtke, Fraunhofer
6  *IPA
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above copyright
16  * notice, this list of conditions and the following disclaimer in the
17  * documentation and/or other materials provided with the distribution.
18  * * Neither the name of the all of the author's companies nor the names of its
19  * contributors may be used to endorse or promote products derived from
20  * this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
23  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
24  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
25  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
26  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
27  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
28  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
29  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
30  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
31  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  *********************************************************************/
35 
36 /*
37  * IKFast Kinematics Solver Plugin for MoveIt wrapping an ikfast solver from OpenRAVE.
38  *
39  * AUTO-GENERATED by create_ikfast_moveit_plugin.py in moveit_kinematics package.
40  *
41  * This file, including the ikfast cpp from OpenRAVE below, forms a MoveIt kinematics plugin.
42  */
43 
44 
45 #include <Eigen/Geometry>
46 #include <rclcpp/logger.hpp>
47 #include <rclcpp/logging.hpp>
48 #include <rclcpp/node.hpp>
49 #include <rclcpp/parameter_value.hpp>
50 #include <tf2_eigen/tf2_eigen.hpp>
51 #include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
52 #include <tf2_kdl/tf2_kdl.hpp>
55 #include <prbt_ikfast_kinematics_parameters.hpp>
56 
57 using namespace moveit::core;
58 
59 // Need a floating point tolerance when checking joint limits, in case the joint starts at limit
60 const double LIMIT_TOLERANCE = .0000001;
63 {
66 };
67 
69 {
70 #define IKFAST_NO_MAIN // Don't include main() from IKFast
71 
78 {
79  IKP_None = 0,
80  IKP_Transform6D = 0x67000001,
81  IKP_Rotation3D = 0x34000002,
82  IKP_Translation3D = 0x33000003,
83  IKP_Direction3D = 0x23000004,
84  IKP_Ray4D = 0x46000005,
85  IKP_Lookat3D = 0x23000006,
89  IKP_TranslationXY2D = 0x22000008,
94 
104 
117 
119 
121  0x00008000,
138 
139  IKP_UniqueIdMask = 0x0000ffff,
140  IKP_CustomDataBit = 0x00010000,
142 };
143 
144 // struct for storing and sorting solutions
146 {
147  std::vector<double> value;
149 
150  bool operator<(const LimitObeyingSol& a) const
151  {
152  return dist_from_seed < a.dist_from_seed;
153  }
154 };
155 
156 static const rclcpp::Logger LOGGER = rclcpp::get_logger("ikfast");
157 
158 // Code generated by IKFast56/61
160 
161 
163 {
164  std::vector<std::string> joint_names_;
165  std::vector<double> joint_min_vector_;
166  std::vector<double> joint_max_vector_;
167  std::vector<bool> joint_has_limits_vector_;
168  std::vector<std::string> link_names_;
169  const size_t num_joints_;
170  std::vector<int> free_params_;
171 
172  std::shared_ptr<prbt_ikfast_kinematics::ParamListener> param_listener_;
173  prbt_ikfast_kinematics::Params params_;
174 
175  // The ikfast and base frame are the start and end of the kinematic chain for which the
176  // IKFast analytic solution was generated.
177  const std::string IKFAST_TIP_FRAME_ = "flange";
178  const std::string IKFAST_BASE_FRAME_ = "base_link";
179 
180  // The transform tip and base bool are set to true if this solver is used with a kinematic
181  // chain that extends beyond the ikfast tip and base frame. The solution will be valid so
182  // long as there are no active, passive, or mimic joints between either the ikfast_tip_frame
183  // and the tip_frame of the group or the ikfast_base_frame and the base_frame for the group.
184  bool tip_transform_required_;
185  bool base_transform_required_;
186 
187  // We store the transform from the ikfast_base_frame to the group base_frame as well as the
188  // ikfast_tip_frame to the group tip_frame to transform input poses into the solver frame.
189  Eigen::Isometry3d chain_base_to_group_base_;
190  Eigen::Isometry3d group_tip_to_chain_tip_;
191 
192  bool initialized_; // Internal variable that indicates whether solvers are configured and ready
193 
194  const std::vector<std::string>& getJointNames() const override
195  {
196  return joint_names_;
197  }
198  const std::vector<std::string>& getLinkNames() const override
199  {
200  return link_names_;
201  }
202 
203 public:
207  IKFastKinematicsPlugin() : num_joints_(GetNumJoints()), initialized_(false)
208  {
209  srand(time(nullptr));
210  supported_methods_.push_back(kinematics::DiscretizationMethods::NO_DISCRETIZATION);
211  supported_methods_.push_back(kinematics::DiscretizationMethods::ALL_DISCRETIZED);
212  supported_methods_.push_back(kinematics::DiscretizationMethods::ALL_RANDOM_SAMPLED);
213  }
214 
224  // Returns the IK solution that is within joint limits closest to ik_seed_state
225  bool getPositionIK(
226  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, std::vector<double>& solution,
227  moveit_msgs::msg::MoveItErrorCodes& error_code,
229 
245  bool getPositionIK(const std::vector<geometry_msgs::msg::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
246  std::vector<std::vector<double>>& solutions, kinematics::KinematicsResult& result,
247  const kinematics::KinematicsQueryOptions& options) const override;
248 
257  bool searchPositionIK(
258  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
259  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
261 
271  bool searchPositionIK(
272  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
273  const std::vector<double>& consistency_limits, std::vector<double>& solution,
274  moveit_msgs::msg::MoveItErrorCodes& error_code,
276 
285  bool searchPositionIK(
286  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
287  std::vector<double>& solution, const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
289 
300  bool searchPositionIK(
301  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
302  const std::vector<double>& consistency_limits, std::vector<double>& solution,
303  const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
305 
314  bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
315  std::vector<geometry_msgs::msg::Pose>& poses) const override;
316 
326  void setSearchDiscretization(const std::map<unsigned int, double>& discretization);
327 
331  bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices) override;
332 
333 private:
334  bool initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model, const std::string& group_name,
335  const std::string& base_frame, const std::vector<std::string>& tip_frames,
336  double search_discretization) override;
337 
342  size_t solve(KDL::Frame& pose_frame, const std::vector<double>& vfree, IkSolutionList<IkReal>& solutions) const;
343 
347  void getSolution(const IkSolutionList<IkReal>& solutions, int i, std::vector<double>& solution) const;
348 
352  void getSolution(const IkSolutionList<IkReal>& solutions, const std::vector<double>& ik_seed_state, int i,
353  std::vector<double>& solution) const;
354 
358  double enforceLimits(double val, double min, double max) const;
359 
360  void fillFreeParams(int count, int* array);
361  bool getCount(int& count, int max_count, int min_count) const;
362 
369  bool sampleRedundantJoint(kinematics::DiscretizationMethod method, std::vector<double>& sampled_joint_vals) const;
370 
372  bool computeRelativeTransform(const std::string& from, const std::string& to, Eigen::Isometry3d& transform,
373  bool& differs_from_identity);
380  void transformToChainFrame(const geometry_msgs::msg::Pose& ik_pose, KDL::Frame& ik_pose_chain) const;
381 }; // end class
382 
383 bool IKFastKinematicsPlugin::computeRelativeTransform(const std::string& from, const std::string& to,
384  Eigen::Isometry3d& transform, bool& differs_from_identity)
385 {
386  RobotStatePtr robot_state = std::make_shared<RobotState>(robot_model_);
387  robot_state->setToDefaultValues();
388 
389  auto* from_link = robot_model_->getLinkModel(from);
390  auto* to_link = robot_model_->getLinkModel(to);
391  if (!from_link || !to_link)
392  return false;
393 
394  if (robot_model_->getRigidlyConnectedParentLinkModel(from_link) !=
395  robot_model_->getRigidlyConnectedParentLinkModel(to_link))
396  {
397  RCLCPP_ERROR_STREAM(LOGGER, "Link frames " << from << " and " << to << " are not rigidly connected.");
398  return false;
399  }
400 
401  transform = robot_state->getGlobalLinkTransform(from_link).inverse() * robot_state->getGlobalLinkTransform(to_link);
402  differs_from_identity = !transform.matrix().isIdentity();
403  return true;
404 }
405 
406 bool IKFastKinematicsPlugin::initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model, const std::string& group_name,
407  const std::string& base_frame, const std::vector<std::string>& tip_frames,
408  double search_discretization)
409 {
410  if (tip_frames.size() != 1)
411  {
412  RCLCPP_ERROR(LOGGER, "Expecting exactly one tip frame.");
413  return false;
414  }
415 
416  std::string kinematics_param_prefix = "robot_description_kinematics." + group_name;
417  param_listener_ = std::make_shared<prbt_ikfast_kinematics::ParamListener>(node, kinematics_param_prefix);
418  params_ = param_listener_->get_params();
419 
420  storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
421 
422  RCLCPP_INFO_STREAM(LOGGER, "Using link_prefix: '" << params_.link_prefix << '\'');
423 
424  // verbose error output. subsequent checks in computeRelativeTransform return false then
425  if (!robot_model.hasLinkModel(tip_frames_[0]))
426  RCLCPP_ERROR_STREAM(LOGGER, "tip frame '" << tip_frames_[0] << "' does not exist.");
427  if (!robot_model.hasLinkModel(base_frame_))
428  RCLCPP_ERROR_STREAM(LOGGER, "base_frame '" << base_frame_ << "' does not exist.");
429 
430  if (!robot_model.hasLinkModel(params_.link_prefix + IKFAST_TIP_FRAME_)) {
431  RCLCPP_ERROR_STREAM(LOGGER, "prefixed tip frame '" << params_.link_prefix + IKFAST_TIP_FRAME_
432  << "' does not exist. "
433  "Please check your link_prefix parameter.");
434  }
435  if (!robot_model.hasLinkModel(params_.link_prefix + IKFAST_BASE_FRAME_)) {
436  RCLCPP_ERROR_STREAM(LOGGER, "prefixed base frame '" << params_.link_prefix + IKFAST_BASE_FRAME_
437  << "' does not exist. "
438  "Please check your link_prefix parameter.");
439  }
440  // This IKFast solution was generated with IKFAST_TIP_FRAME_ and IKFAST_BASE_FRAME_.
441  // It is often the case that fixed joints are added to these links to model things like
442  // a robot mounted on a table or a robot with an end effector attached to the last link.
443  // To support these use cases, we store the transform from the IKFAST_BASE_FRAME_ to the
444  // base_frame_ and IKFAST_TIP_FRAME_ the tip_frame_ and transform to the input pose accordingly
445  if (!computeRelativeTransform(tip_frames_[0], params_.link_prefix + IKFAST_TIP_FRAME_, group_tip_to_chain_tip_,
446  tip_transform_required_) ||
447  !computeRelativeTransform(params_.link_prefix + IKFAST_BASE_FRAME_, base_frame_, chain_base_to_group_base_,
448  base_transform_required_))
449  {
450  return false;
451  }
452 
453  // IKFast56/61
454  fillFreeParams(GetNumFreeParameters(), GetFreeParameters());
455 
456  if (free_params_.size() > 1)
457  {
458  RCLCPP_ERROR(LOGGER, "Only one free joint parameter supported!");
459  return false;
460  }
461  else if (free_params_.size() == 1)
462  {
463  redundant_joint_indices_.clear();
464  redundant_joint_indices_.push_back(free_params_[0]);
465  KinematicsBase::setSearchDiscretization(search_discretization);
466  }
467 
468  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group_name);
469  if (!jmg)
470  {
471  RCLCPP_ERROR_STREAM(LOGGER, "Unknown planning group: " << group_name);
472  return false;
473  }
474 
475  RCLCPP_DEBUG_STREAM(LOGGER, "Registering joints and links");
476  const moveit::core::LinkModel* link = robot_model_->getLinkModel(tip_frames_[0]);
477  const moveit::core::LinkModel* base_link = robot_model_->getLinkModel(base_frame_);
478  while (link && link != base_link)
479  {
480  RCLCPP_DEBUG_STREAM(LOGGER, "Link " << link->getName());
481  link_names_.push_back(link->getName());
482  const moveit::core::JointModel* joint = link->getParentJointModel();
483  if (joint->getType() != joint->UNKNOWN && joint->getType() != joint->FIXED && joint->getVariableCount() == 1)
484  {
485  RCLCPP_DEBUG_STREAM(LOGGER, "Adding joint " << joint->getName());
486 
487  joint_names_.push_back(joint->getName());
488  const moveit::core::VariableBounds& bounds = joint->getVariableBounds()[0];
489  joint_has_limits_vector_.push_back(bounds.position_bounded_);
490  joint_min_vector_.push_back(bounds.min_position_);
491  joint_max_vector_.push_back(bounds.max_position_);
492  }
493  link = link->getParentLinkModel();
494  }
495 
496  if (joint_names_.size() != num_joints_)
497  {
498  RCLCPP_FATAL(LOGGER, "Joint numbers of RobotModel (%zd) and IKFast solver (%zd) do not match", joint_names_.size(),
499  num_joints_);
500  return false;
501  }
502 
503  std::reverse(link_names_.begin(), link_names_.end());
504  std::reverse(joint_names_.begin(), joint_names_.end());
505  std::reverse(joint_min_vector_.begin(), joint_min_vector_.end());
506  std::reverse(joint_max_vector_.begin(), joint_max_vector_.end());
507  std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end());
508 
509  for (size_t joint_id = 0; joint_id < num_joints_; ++joint_id) {
510  RCLCPP_DEBUG_STREAM(LOGGER, joint_names_[joint_id] << ' ' << joint_min_vector_[joint_id] << ' '
511  << joint_max_vector_[joint_id] << ' '
512  << joint_has_limits_vector_[joint_id]);
513  }
514 
515  initialized_ = true;
516  return true;
517 }
518 
519 void IKFastKinematicsPlugin::setSearchDiscretization(const std::map<unsigned int, double>& discretization)
520 {
521  if (discretization.empty())
522  {
523  RCLCPP_ERROR(LOGGER, "The 'discretization' map is empty");
524  return;
525  }
526 
527  if (redundant_joint_indices_.empty())
528  {
529  RCLCPP_ERROR_STREAM(LOGGER, "This group's solver doesn't support redundant joints");
530  return;
531  }
532 
533  if (discretization.begin()->first != redundant_joint_indices_[0])
534  {
535  std::string redundant_joint = joint_names_[free_params_[0]];
536  RCLCPP_ERROR_STREAM(LOGGER, "Attempted to discretize a non-redundant joint "
537  << discretization.begin()->first << ", only joint '" << redundant_joint
538  << "' with index " << redundant_joint_indices_[0] << " is redundant.");
539  return;
540  }
541 
542  if (discretization.begin()->second <= 0.0)
543  {
544  RCLCPP_ERROR_STREAM(LOGGER, "Discretization can not takes values that are <= 0");
545  return;
546  }
547 
548  redundant_joint_discretization_.clear();
549  redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second;
550 }
551 
552 bool IKFastKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int>& /* unused */)
553 {
554  RCLCPP_ERROR_STREAM(LOGGER, "Changing the redundant joints isn't permitted by this group's solver ");
555  return false;
556 }
557 
558 size_t IKFastKinematicsPlugin::solve(KDL::Frame& pose_frame, const std::vector<double>& vfree,
559  IkSolutionList<IkReal>& solutions) const
560 {
561  // IKFast56/61
562  solutions.Clear();
563 
564  double trans[3];
565  trans[0] = pose_frame.p[0]; //-.18;
566  trans[1] = pose_frame.p[1];
567  trans[2] = pose_frame.p[2];
568 
569  KDL::Rotation mult;
570  KDL::Vector direction;
571 
572  switch (GetIkType())
573  {
574  case IKP_Transform6D:
575  case IKP_Translation3D:
576  // For **Transform6D**, eerot is 9 values for the 3x3 rotation matrix. For **Translation3D**, these are ignored.
577 
578  mult = pose_frame.M;
579 
580  double vals[9];
581  vals[0] = mult(0, 0);
582  vals[1] = mult(0, 1);
583  vals[2] = mult(0, 2);
584  vals[3] = mult(1, 0);
585  vals[4] = mult(1, 1);
586  vals[5] = mult(1, 2);
587  vals[6] = mult(2, 0);
588  vals[7] = mult(2, 1);
589  vals[8] = mult(2, 2);
590 
591  // IKFast56/61
592  ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
593  return solutions.GetNumSolutions();
594 
595  case IKP_Direction3D:
596  case IKP_Ray4D:
598  // For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target
599  // direction.
600 
601  direction = pose_frame.M * KDL::Vector(0, 0, 1);
602  ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
603  return solutions.GetNumSolutions();
604 
608  // For *TranslationXAxisAngle4D*, *TranslationYAxisAngle4D*, *TranslationZAxisAngle4D* - end effector origin
609  // reaches desired 3D translation, manipulator direction makes a specific angle with x/y/z-axis (defined in the
610  // manipulator base link’s coordinate system)
611  RCLCPP_ERROR(LOGGER, "IK for this IkParameterizationType not implemented yet.");
612  return 0;
613 
615  // For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end
616  // effector coordinate system.
617  RCLCPP_ERROR(LOGGER, "IK for this IkParameterizationType not implemented yet.");
618  return 0;
619 
620  case IKP_Rotation3D:
621  case IKP_Lookat3D:
622  case IKP_TranslationXY2D:
624  RCLCPP_ERROR(LOGGER, "IK for this IkParameterizationType not implemented yet.");
625  return 0;
626 
628  double roll, pitch, yaw;
629  // For **TranslationXAxisAngleZNorm4D** - end effector origin reaches desired 3D translation, manipulator
630  // direction needs to be orthogonal to z axis and be rotated at a certain angle starting from the x axis (defined
631  // in the manipulator base link’s coordinate system)
632  pose_frame.M.GetRPY(roll, pitch, yaw);
633  ComputeIk(trans, &yaw, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
634  return solutions.GetNumSolutions();
635 
637  // For **TranslationYAxisAngleXNorm4D** - end effector origin reaches desired 3D translation, manipulator
638  // direction needs to be orthogonal to x axis and be rotated at a certain angle starting from the y axis (defined
639  // in the manipulator base link’s coordinate system)
640  pose_frame.M.GetRPY(roll, pitch, yaw);
641  ComputeIk(trans, &roll, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
642  return solutions.GetNumSolutions();
643 
645  // For **TranslationZAxisAngleYNorm4D** - end effector origin reaches desired 3D translation, manipulator
646  // direction needs to be orthogonal to y axis and be rotated at a certain angle starting from the z axis (defined
647  // in the manipulator base link’s coordinate system)
648  pose_frame.M.GetRPY(roll, pitch, yaw);
649  ComputeIk(trans, &pitch, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
650  return solutions.GetNumSolutions();
651 
652  default:
653  RCLCPP_ERROR(LOGGER, "Unknown IkParameterizationType! "
654  "Was the solver generated with an incompatible version of Openrave?");
655  return 0;
656  }
657 }
658 
659 void IKFastKinematicsPlugin::getSolution(const IkSolutionList<IkReal>& solutions, int i,
660  std::vector<double>& solution) const
661 {
662  solution.clear();
663  solution.resize(num_joints_);
664 
665  // IKFast56/61
666  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
667  std::vector<IkReal> vsolfree(sol.GetFree().size());
668  sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : nullptr);
669 
670  for (std::size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
671  {
672  if (joint_has_limits_vector_[joint_id])
673  {
674  solution[joint_id] = enforceLimits(solution[joint_id], joint_min_vector_[joint_id], joint_max_vector_[joint_id]);
675  }
676  }
677 }
678 
679 void IKFastKinematicsPlugin::getSolution(const IkSolutionList<IkReal>& solutions,
680  const std::vector<double>& ik_seed_state, int i,
681  std::vector<double>& solution) const
682 {
683  solution.clear();
684  solution.resize(num_joints_);
685 
686  // IKFast56/61
687  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
688  std::vector<IkReal> vsolfree(sol.GetFree().size());
689  sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : nullptr);
690 
691  // rotate joints by +/-360° where it is possible and useful
692  for (std::size_t i = 0; i < num_joints_; ++i)
693  {
694  if (joint_has_limits_vector_[i])
695  {
696  solution[i] = enforceLimits(solution[i], joint_min_vector_[i], joint_max_vector_[i]);
697  double signed_distance = solution[i] - ik_seed_state[i];
698  while (signed_distance > M_PI && solution[i] - 2 * M_PI > (joint_min_vector_[i] - LIMIT_TOLERANCE))
699  {
700  signed_distance -= 2 * M_PI;
701  solution[i] -= 2 * M_PI;
702  }
703  while (signed_distance < -M_PI && solution[i] + 2 * M_PI < (joint_max_vector_[i] + LIMIT_TOLERANCE))
704  {
705  signed_distance += 2 * M_PI;
706  solution[i] += 2 * M_PI;
707  }
708  }
709  }
710 }
711 
712 double IKFastKinematicsPlugin::enforceLimits(double joint_value, double min, double max) const
713 {
714  // If the joint_value is greater than max subtract 2 * PI until it is less than the max
715  while (joint_value > max)
716  {
717  joint_value -= 2 * M_PI;
718  }
719 
720  // If the joint_value is less than the min, add 2 * PI until it is more than the min
721  while (joint_value < min)
722  {
723  joint_value += 2 * M_PI;
724  }
725  return joint_value;
726 }
727 
728 void IKFastKinematicsPlugin::fillFreeParams(int count, int* array)
729 {
730  free_params_.clear();
731  for (int i = 0; i < count; ++i)
732  free_params_.push_back(array[i]);
733 }
734 
735 bool IKFastKinematicsPlugin::getCount(int& count, int max_count, int min_count) const
736 {
737  if (count > 0)
738  {
739  if (-count >= min_count)
740  {
741  count = -count;
742  return true;
743  }
744  else if (count + 1 <= max_count)
745  {
746  count = count + 1;
747  return true;
748  }
749  else
750  {
751  return false;
752  }
753  }
754  else
755  {
756  if (1 - count <= max_count)
757  {
758  count = 1 - count;
759  return true;
760  }
761  else if (count - 1 >= min_count)
762  {
763  count = count - 1;
764  return true;
765  }
766  else
767  return false;
768  }
769 }
770 
771 bool IKFastKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
772  const std::vector<double>& joint_angles,
773  std::vector<geometry_msgs::msg::Pose>& poses) const
774 {
775  if (GetIkType() != IKP_Transform6D)
776  {
777  // ComputeFk() is the inverse function of ComputeIk(), so the format of
778  // eerot differs depending on IK type. The Transform6D IK type is the only
779  // one for which a 3x3 rotation matrix is returned, which means we can only
780  // compute FK for that IK type.
781  RCLCPP_ERROR(LOGGER, "Can only compute FK for Transform6D IK type!");
782  return false;
783  }
784 
785  KDL::Frame p_out;
786  if (link_names.size() == 0)
787  {
788  RCLCPP_WARN_STREAM(LOGGER, "Link names with nothing");
789  return false;
790  }
791 
792  if (link_names.size() != 1 || link_names[0] != getTipFrame())
793  {
794  RCLCPP_ERROR(LOGGER, "Can compute FK for %s only", getTipFrame().c_str());
795  return false;
796  }
797 
798  bool valid = true;
799 
800  IkReal eerot[9], eetrans[3];
801 
802  if (joint_angles.size() != num_joints_)
803  {
804  RCLCPP_ERROR(LOGGER, "Unexpected number of joint angles");
805  return false;
806  }
807 
808  std::vector<IkReal> angles(num_joints_, 0);
809  for (unsigned char i = 0; i < num_joints_; i++)
810  angles[i] = joint_angles[i];
811 
812  // IKFast56/61
813  ComputeFk(angles.data(), eetrans, eerot);
814 
815  for (int i = 0; i < 3; ++i)
816  p_out.p.data[i] = eetrans[i];
817 
818  for (int i = 0; i < 9; ++i)
819  p_out.M.data[i] = eerot[i];
820 
821  poses.resize(1);
822  poses[0] = tf2::toMsg(p_out);
823 
824  return valid;
825 }
826 
827 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
828  const std::vector<double>& ik_seed_state, double timeout,
829  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
831 {
832  std::vector<double> consistency_limits;
833  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
834  options);
835 }
836 
837 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
838  const std::vector<double>& ik_seed_state, double timeout,
839  const std::vector<double>& consistency_limits,
840  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
842 {
843  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
844  options);
845 }
846 
847 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
848  const std::vector<double>& ik_seed_state, double timeout,
849  std::vector<double>& solution, const IKCallbackFn& solution_callback,
850  moveit_msgs::msg::MoveItErrorCodes& error_code,
852 {
853  std::vector<double> consistency_limits;
854  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
855  options);
856 }
857 
858 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
859  const std::vector<double>& ik_seed_state, double /* unused */,
860  const std::vector<double>& consistency_limits,
861  std::vector<double>& solution, const IKCallbackFn& solution_callback,
862  moveit_msgs::msg::MoveItErrorCodes& error_code,
864 {
865  // "SEARCH_MODE" is fixed during code generation
866  SEARCH_MODE search_mode = OPTIMIZE_MAX_JOINT;
867 
868  // Check if there are no redundant joints
869  if (free_params_.size() == 0)
870  {
871  RCLCPP_DEBUG_STREAM(LOGGER, "No need to search since no free params/redundant joints");
872 
873  std::vector<geometry_msgs::msg::Pose> ik_poses(1, ik_pose);
874  std::vector<std::vector<double>> solutions;
875  kinematics::KinematicsResult kinematic_result;
876  // Find all IK solutions within joint limits
877  if (!getPositionIK(ik_poses, ik_seed_state, solutions, kinematic_result, options))
878  {
879  RCLCPP_DEBUG_STREAM(LOGGER, "No solution whatsoever");
880  error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
881  return false;
882  }
883 
884  // sort solutions by their distance to the seed
885  std::vector<LimitObeyingSol> solutions_obey_limits;
886  for (std::size_t i = 0; i < solutions.size(); ++i)
887  {
888  double dist_from_seed = 0.0;
889  for (std::size_t j = 0; j < ik_seed_state.size(); ++j)
890  {
891  dist_from_seed += fabs(ik_seed_state[j] - solutions[i][j]);
892  }
893 
894  solutions_obey_limits.push_back({ solutions[i], dist_from_seed });
895  }
896  std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
897 
898  // check for collisions if a callback is provided
899  if (solution_callback)
900  {
901  for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i)
902  {
903  solution_callback(ik_pose, solutions_obey_limits[i].value, error_code);
904  if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
905  {
906  solution = solutions_obey_limits[i].value;
907  RCLCPP_DEBUG_STREAM(LOGGER, "Solution passes callback");
908  return true;
909  }
910  }
911 
912  RCLCPP_DEBUG_STREAM(LOGGER, "Solution has error code " << error_code.val);
913  return false;
914  }
915  else
916  {
917  solution = solutions_obey_limits[0].value;
918  error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
919  return true; // no collision check callback provided
920  }
921  }
922 
923  // -------------------------------------------------------------------------------------------------
924  // Error Checking
925  if (!initialized_)
926  {
927  RCLCPP_ERROR_STREAM(LOGGER, "Kinematics not active");
928  error_code.val = error_code.NO_IK_SOLUTION;
929  return false;
930  }
931 
932  if (ik_seed_state.size() != num_joints_)
933  {
934  RCLCPP_ERROR_STREAM(LOGGER,
935  "Seed state must have size " << num_joints_ << " instead of size " << ik_seed_state.size());
936  error_code.val = error_code.NO_IK_SOLUTION;
937  return false;
938  }
939 
940  if (!consistency_limits.empty() && consistency_limits.size() != num_joints_)
941  {
942  RCLCPP_ERROR_STREAM(LOGGER, "Consistency limits be empty or must have size " << num_joints_ << " instead of size "
943  << consistency_limits.size());
944  error_code.val = error_code.NO_IK_SOLUTION;
945  return false;
946  }
947 
948  // -------------------------------------------------------------------------------------------------
949  // Initialize
950 
951  KDL::Frame frame;
952  transformToChainFrame(ik_pose, frame);
953 
954  std::vector<double> vfree(free_params_.size());
955 
956  int counter = 0;
957 
958  double initial_guess = ik_seed_state[free_params_[0]];
959  vfree[0] = initial_guess;
960 
961  // -------------------------------------------------------------------------------------------------
962  // Handle consistency limits if needed
963  int num_positive_increments;
964  int num_negative_increments;
965  double search_discretization = redundant_joint_discretization_.at(free_params_[0]);
966 
967  if (!consistency_limits.empty())
968  {
969  // MoveIt replaced consistency_limit (scalar) w/ consistency_limits (vector)
970  // Assume [0]th free_params element for now. Probably wrong.
971  double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess + consistency_limits[free_params_[0]]);
972  double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess - consistency_limits[free_params_[0]]);
973 
974  num_positive_increments = static_cast<int>((max_limit - initial_guess) / search_discretization);
975  num_negative_increments = static_cast<int>((initial_guess - min_limit) / search_discretization);
976  }
977  else // no consistency limits provided
978  {
979  num_positive_increments = (joint_max_vector_[free_params_[0]] - initial_guess) / search_discretization;
980  num_negative_increments = (initial_guess - joint_min_vector_[free_params_[0]]) / search_discretization;
981  }
982 
983  // -------------------------------------------------------------------------------------------------
984  // Begin searching
985 
986  RCLCPP_DEBUG_STREAM(LOGGER, "Free param is " << free_params_[0] << " initial guess is " << initial_guess
987  << ", # positive increments: " << num_positive_increments
988  << ", # negative increments: " << num_negative_increments);
989  if ((search_mode & OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000)
990  RCLCPP_WARN_STREAM_ONCE(LOGGER, "Large search space, consider increasing the search discretization");
991 
992  double best_costs = -1.0;
993  std::vector<double> best_solution;
994  int nattempts = 0, nvalid = 0;
995 
996  while (true)
997  {
998  IkSolutionList<IkReal> solutions;
999  size_t numsol = solve(frame, vfree, solutions);
1000 
1001  RCLCPP_DEBUG_STREAM(LOGGER, "Found " << numsol << " solutions from IKFast");
1002 
1003  if (numsol > 0)
1004  {
1005  for (size_t s = 0; s < numsol; ++s)
1006  {
1007  nattempts++;
1008  std::vector<double> sol;
1009  getSolution(solutions, ik_seed_state, s, sol);
1010 
1011  bool obeys_limits = true;
1012  for (size_t i = 0; i < sol.size(); i++)
1013  {
1014  if (joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
1015  {
1016  obeys_limits = false;
1017  break;
1018  }
1019  // RCLCPP_INFO_STREAM(LOGGER,"Num " << i << " value " << sol[i] << " has limits " <<
1020  // joint_has_limits_vector_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i]);
1021  }
1022  if (obeys_limits)
1023  {
1024  getSolution(solutions, ik_seed_state, s, solution);
1025 
1026  // This solution is within joint limits, now check if in collision (if callback provided)
1027  if (solution_callback)
1028  {
1029  solution_callback(ik_pose, solution, error_code);
1030  }
1031  else
1032  {
1033  error_code.val = error_code.SUCCESS;
1034  }
1035 
1036  if (error_code.val == error_code.SUCCESS)
1037  {
1038  nvalid++;
1039  if (search_mode & OPTIMIZE_MAX_JOINT)
1040  {
1041  // Costs for solution: Largest joint motion
1042  double costs = 0.0;
1043  for (unsigned int i = 0; i < solution.size(); i++)
1044  {
1045  double d = fabs(ik_seed_state[i] - solution[i]);
1046  if (d > costs)
1047  costs = d;
1048  }
1049  if (costs < best_costs || best_costs == -1.0)
1050  {
1051  best_costs = costs;
1052  best_solution = solution;
1053  }
1054  }
1055  else {
1056  // Return first feasible solution
1057  return true;
1058  }
1059  }
1060  }
1061  }
1062  }
1063 
1064  if (!getCount(counter, num_positive_increments, -num_negative_increments))
1065  {
1066  // Everything searched
1067  error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
1068  break;
1069  }
1070 
1071  vfree[0] = initial_guess + search_discretization * counter;
1072  // RCLCPP_DEBUG_STREAM(LOGGER,"Attempt " << counter << " with 0th free joint having value " << vfree[0]);
1073  }
1074 
1075  RCLCPP_DEBUG_STREAM(LOGGER, "Valid solutions: " << nvalid << '/' << nattempts);
1076 
1077  if ((search_mode & OPTIMIZE_MAX_JOINT) && best_costs != -1.0)
1078  {
1079  solution = best_solution;
1080  error_code.val = error_code.SUCCESS;
1081  return true;
1082  }
1083 
1084  // No solution found
1085  error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
1086  return false;
1087 }
1088 
1089 // Used when there are no redundant joints - aka no free params
1090 bool IKFastKinematicsPlugin::getPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
1091  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
1092  const kinematics::KinematicsQueryOptions& /* unused */) const
1093 {
1094  RCLCPP_DEBUG_STREAM(LOGGER, "getPositionIK");
1095 
1096  if (!initialized_)
1097  {
1098  RCLCPP_ERROR(LOGGER, "kinematics not active");
1099  return false;
1100  }
1101 
1102  if (ik_seed_state.size() < num_joints_)
1103  {
1104  RCLCPP_ERROR_STREAM(LOGGER, "ik_seed_state only has " << ik_seed_state.size()
1105  << " entries, this ikfast solver requires " << num_joints_);
1106  return false;
1107  }
1108 
1109  // Check if seed is in bound
1110  for (std::size_t i = 0; i < ik_seed_state.size(); i++)
1111  {
1112  // Add tolerance to limit check
1113  if (joint_has_limits_vector_[i] && ((ik_seed_state[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1114  (ik_seed_state[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1115  {
1116  RCLCPP_DEBUG_STREAM(LOGGER, "IK seed not in limits! " << static_cast<int>(i) << " value " << ik_seed_state[i]
1117  << " has limit: " << joint_has_limits_vector_[i] << " being "
1118  << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
1119  return false;
1120  }
1121  }
1122 
1123  std::vector<double> vfree(free_params_.size());
1124  for (std::size_t i = 0; i < free_params_.size(); ++i)
1125  {
1126  int p = free_params_[i];
1127  RCLCPP_ERROR(LOGGER, "%u is %f", p, ik_seed_state[p]); // DTC
1128  vfree[i] = ik_seed_state[p];
1129  }
1130 
1131  KDL::Frame frame;
1132  transformToChainFrame(ik_pose, frame);
1133 
1134  IkSolutionList<IkReal> solutions;
1135  size_t numsol = solve(frame, vfree, solutions);
1136  RCLCPP_DEBUG_STREAM(LOGGER, "Found " << numsol << " solutions from IKFast");
1137 
1138  std::vector<LimitObeyingSol> solutions_obey_limits;
1139 
1140  if (numsol)
1141  {
1142  std::vector<double> solution_obey_limits;
1143  for (std::size_t s = 0; s < numsol; ++s)
1144  {
1145  std::vector<double> sol;
1146  getSolution(solutions, ik_seed_state, s, sol);
1147  RCLCPP_DEBUG(LOGGER, "Sol %d: %e %e %e %e %e %e", static_cast<int>(s), sol[0], sol[1], sol[2], sol[3],
1148  sol[4], sol[5]);
1149 
1150  bool obeys_limits = true;
1151  for (std::size_t i = 0; i < sol.size(); i++)
1152  {
1153  // Add tolerance to limit check
1154  if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1155  (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1156  {
1157  // One element of solution is not within limits
1158  obeys_limits = false;
1159  RCLCPP_DEBUG_STREAM(LOGGER, "Not in limits! " << static_cast<int>(i) << " value " << sol[i]
1160  << " has limit: " << joint_has_limits_vector_[i] << " being "
1161  << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
1162  break;
1163  }
1164  }
1165  if (obeys_limits)
1166  {
1167  // All elements of this solution obey limits
1168  getSolution(solutions, ik_seed_state, s, solution_obey_limits);
1169  double dist_from_seed = 0.0;
1170  for (std::size_t i = 0; i < ik_seed_state.size(); ++i)
1171  {
1172  dist_from_seed += fabs(ik_seed_state[i] - solution_obey_limits[i]);
1173  }
1174 
1175  solutions_obey_limits.push_back({ solution_obey_limits, dist_from_seed });
1176  }
1177  }
1178  }
1179  else
1180  {
1181  RCLCPP_DEBUG_STREAM(LOGGER, "No IK solution");
1182  }
1183 
1184  // Sort the solutions under limits and find the one that is closest to ik_seed_state
1185  if (!solutions_obey_limits.empty())
1186  {
1187  std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
1188  solution = solutions_obey_limits[0].value;
1189  error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
1190  return true;
1191  }
1192 
1193  error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
1194  return false;
1195 }
1196 
1197 bool IKFastKinematicsPlugin::getPositionIK(const std::vector<geometry_msgs::msg::Pose>& ik_poses,
1198  const std::vector<double>& ik_seed_state,
1199  std::vector<std::vector<double>>& solutions,
1202 {
1203  RCLCPP_DEBUG_STREAM(LOGGER, "getPositionIK with multiple solutions");
1204 
1205  if (!initialized_)
1206  {
1207  RCLCPP_ERROR(LOGGER, "kinematics not active");
1209  return false;
1210  }
1211 
1212  if (ik_poses.empty())
1213  {
1214  RCLCPP_ERROR(LOGGER, "ik_poses is empty");
1216  return false;
1217  }
1218 
1219  if (ik_poses.size() > 1)
1220  {
1221  RCLCPP_ERROR(LOGGER, "ik_poses contains multiple entries, only one is allowed");
1223  return false;
1224  }
1225 
1226  if (ik_seed_state.size() < num_joints_)
1227  {
1228  RCLCPP_ERROR_STREAM(LOGGER, "ik_seed_state only has " << ik_seed_state.size()
1229  << " entries, this ikfast solver requires " << num_joints_);
1230  return false;
1231  }
1232 
1233  KDL::Frame frame;
1234  transformToChainFrame(ik_poses[0], frame);
1235 
1236  // solving ik
1237  std::vector<IkSolutionList<IkReal>> solution_set;
1238  IkSolutionList<IkReal> ik_solutions;
1239  std::vector<double> vfree;
1240  int numsol = 0;
1241  std::vector<double> sampled_joint_vals;
1242  if (!redundant_joint_indices_.empty())
1243  {
1244  // initializing from seed
1245  sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]);
1246 
1247  // checking joint limits when using no discretization
1248  if (options.discretization_method == kinematics::DiscretizationMethods::NO_DISCRETIZATION &&
1249  joint_has_limits_vector_[redundant_joint_indices_.front()])
1250  {
1251  double joint_min = joint_min_vector_[redundant_joint_indices_.front()];
1252  double joint_max = joint_max_vector_[redundant_joint_indices_.front()];
1253 
1254  double jv = sampled_joint_vals[0];
1255  if (!((jv > (joint_min - LIMIT_TOLERANCE)) && (jv < (joint_max + LIMIT_TOLERANCE))))
1256  {
1258  RCLCPP_ERROR_STREAM(LOGGER, "ik seed is out of bounds");
1259  return false;
1260  }
1261  }
1262 
1263  // computing all solutions sets for each sampled value of the redundant joint
1264  if (!sampleRedundantJoint(options.discretization_method, sampled_joint_vals))
1265  {
1267  return false;
1268  }
1269 
1270  for (unsigned int i = 0; i < sampled_joint_vals.size(); i++)
1271  {
1272  vfree.clear();
1273  vfree.push_back(sampled_joint_vals[i]);
1274  numsol += solve(frame, vfree, ik_solutions);
1275  solution_set.push_back(ik_solutions);
1276  }
1277  }
1278  else
1279  {
1280  // computing for single solution set
1281  numsol = solve(frame, vfree, ik_solutions);
1282  solution_set.push_back(ik_solutions);
1283  }
1284 
1285  RCLCPP_DEBUG_STREAM(LOGGER, "Found " << numsol << " solutions from IKFast");
1286  bool solutions_found = false;
1287  if (numsol > 0)
1288  {
1289  /*
1290  Iterating through all solution sets and storing those that do not exceed joint limits.
1291  */
1292  for (unsigned int r = 0; r < solution_set.size(); r++)
1293  {
1294  ik_solutions = solution_set[r];
1295  numsol = ik_solutions.GetNumSolutions();
1296  for (int s = 0; s < numsol; ++s)
1297  {
1298  std::vector<double> sol;
1299  getSolution(ik_solutions, ik_seed_state, s, sol);
1300 
1301  bool obeys_limits = true;
1302  for (unsigned int i = 0; i < sol.size(); i++)
1303  {
1304  // Add tolerance to limit check
1305  if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) ||
1306  (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE))))
1307  {
1308  // One element of solution is not within limits
1309  obeys_limits = false;
1310  RCLCPP_DEBUG_STREAM(LOGGER, "Not in limits! " << i << " value " << sol[i]
1311  << " has limit: " << joint_has_limits_vector_[i] << " being "
1312  << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
1313  break;
1314  }
1315  }
1316  if (obeys_limits)
1317  {
1318  // All elements of solution obey limits
1319  solutions_found = true;
1320  solutions.push_back(sol);
1321  }
1322  }
1323  }
1324 
1325  if (solutions_found)
1326  {
1328  return true;
1329  }
1330  }
1331  else
1332  {
1333  RCLCPP_DEBUG_STREAM(LOGGER, "No IK solution");
1334  }
1335 
1337  return false;
1338 }
1339 
1340 bool IKFastKinematicsPlugin::sampleRedundantJoint(kinematics::DiscretizationMethod method,
1341  std::vector<double>& sampled_joint_vals) const
1342 {
1343  int index = redundant_joint_indices_.front();
1344  double joint_dscrt = redundant_joint_discretization_.at(index);
1345  double joint_min = joint_min_vector_[index];
1346  double joint_max = joint_max_vector_[index];
1347 
1348  switch (method)
1349  {
1351  {
1352  size_t steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1353  for (size_t i = 0; i < steps; i++)
1354  {
1355  sampled_joint_vals.push_back(joint_min + joint_dscrt * i);
1356  }
1357  sampled_joint_vals.push_back(joint_max);
1358  }
1359  break;
1361  {
1362  int steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1363  steps = steps > 0 ? steps : 1;
1364  double diff = joint_max - joint_min;
1365  for (int i = 0; i < steps; i++)
1366  {
1367  sampled_joint_vals.push_back(((diff * std::rand()) / (static_cast<double>(RAND_MAX))) + joint_min);
1368  }
1369  }
1370 
1371  break;
1373 
1374  break;
1375  default:
1376  RCLCPP_ERROR_STREAM(LOGGER, "Discretization method " << method << " is not supported");
1377  return false;
1378  }
1379 
1380  return true;
1381 }
1382 
1383 void IKFastKinematicsPlugin::transformToChainFrame(const geometry_msgs::msg::Pose& ik_pose, KDL::Frame& ik_pose_chain) const
1384 {
1385  if (tip_transform_required_ || base_transform_required_)
1386  {
1387  Eigen::Isometry3d ik_eigen_pose;
1388  tf2::fromMsg(ik_pose, ik_eigen_pose);
1389  if (tip_transform_required_)
1390  ik_eigen_pose = ik_eigen_pose * group_tip_to_chain_tip_;
1391 
1392  if (base_transform_required_)
1393  ik_eigen_pose = chain_base_to_group_base_ * ik_eigen_pose;
1394 
1395  tf2::transformEigenToKDL(ik_eigen_pose, ik_pose_chain);
1396  }
1397  else
1398  {
1399  tf2::fromMsg(ik_pose, ik_pose_chain);
1400  }
1401 }
1402 
1403 } // namespace prbt_manipulator
1404 
1405 // register IKFastKinematicsPlugin as a KinematicsBase implementation
1406 #include <pluginlib/class_list_macros.hpp>
The discrete solutions are returned in this structure.
Definition: ikfast.h:73
virtual const std::vector< int > & GetFree() const =0
Gets the indices of the configuration space that have to be preset before a full solution can be retu...
virtual void GetSolution(T *solution, const T *freevalues) const =0
gets a concrete solution
Default implementation of IkSolutionListBase.
Definition: ikfast.h:277
virtual const IkSolutionBase< T > & GetSolution(size_t index) const
returns the solution pointer
Definition: ikfast.h:286
virtual size_t GetNumSolutions() const
returns the number of solutions stored
Definition: ikfast.h:297
virtual void Clear()
clears all current solutions, note that any memory addresses returned from GetSolution will be invali...
Definition: ikfast.h:302
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....
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
const std::string & getName() const
Get the name of the joint.
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.
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.hpp:72
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
Definition: link_model.hpp:108
const std::string & getName() const
The name of this link.
Definition: link_model.hpp: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.hpp:117
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.hpp:76
bool hasLinkModel(const std::string &name) const
Check if a link exists. Return true if it does.
SEARCH_MODE
Search modes for searchPositionIK(), see there.
Core components of MoveIt.
IkParameterizationType
The types of inverse kinematics parameterizations supported.
@ IKP_Direction3D
direction on end effector coordinate system reaches desired direction
@ IKP_UniqueIdMask
the mask for the unique ids
@ IKP_TranslationXY2D
2D translation along XY plane
@ IKP_NumberOfParameterizations
number of parameterizations (does not count IKP_None)
@ IKP_TranslationLocalGlobal6D
local point on end effector origin reaches desired 3D global point
@ IKP_Ray4D
ray on end effector coordinate system reaches desired global ray
@ IKP_Translation3D
end effector origin reaches desired 3D translation
@ IKP_Rotation3D
end effector reaches desired 3D rotation
@ IKP_VelocityDataBit
bit is set if the data represents the time-derivate velocity of an IkParameterization
@ IKP_Transform6D
end effector reaches desired 6D transformation
@ IKP_Lookat3D
direction on end effector coordinate system points to desired 3D position
PLUGINLIB_EXPORT_CLASS(prbt_manipulator::IKFastKinematicsPlugin, kinematics::KinematicsBase)
const double LIMIT_TOLERANCE
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()
A set of options for the kinematics solver.