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