44 #include <rclcpp/rclcpp.hpp>
47 #include <Eigen/Geometry>
48 #include <tf2_kdl/tf2_kdl.hpp>
49 #include <tf2_eigen/tf2_eigen.hpp>
64 #define IKFAST_NO_MAIN
146 return dist_from_seed <
a.dist_from_seed;
151 #include "_ROBOT_NAME___GROUP_NAME__ikfast_solver.cpp"
155 std::vector<std::string> joint_names_;
156 std::vector<double> joint_min_vector_;
157 std::vector<double> joint_max_vector_;
158 std::vector<bool> joint_has_limits_vector_;
159 std::vector<std::string> link_names_;
160 const size_t num_joints_;
161 std::vector<int> free_params_;
165 const std::string IKFAST_TIP_FRAME_ =
"_EEF_LINK_";
166 const std::string IKFAST_BASE_FRAME_ =
"_BASE_LINK_";
169 std::string link_prefix_;
175 bool tip_transform_required_;
176 bool base_transform_required_;
180 Eigen::Isometry3d chain_base_to_group_base_;
181 Eigen::Isometry3d group_tip_to_chain_tip_;
184 const rclcpp::Logger LOGGER = rclcpp::get_logger(
"_ROBOT_NAME___GROUP_NAME__ikfast_solver");
186 const std::vector<std::string>& getJointNames()
const override
190 const std::vector<std::string>& getLinkNames()
const override
201 srand(time(
nullptr));
218 getPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
219 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
237 bool getPositionIK(
const std::vector<geometry_msgs::msg::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
249 bool searchPositionIK(
250 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
251 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
263 bool searchPositionIK(
264 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
265 const std::vector<double>& consistency_limits, std::vector<double>& solution,
266 moveit_msgs::msg::MoveItErrorCodes& error_code,
277 bool searchPositionIK(
278 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
279 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
280 moveit_msgs::msg::MoveItErrorCodes& error_code,
293 bool searchPositionIK(
294 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
295 const std::vector<double>& consistency_limits, std::vector<double>& solution,
296 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
307 bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
308 std::vector<geometry_msgs::msg::Pose>& poses)
const override;
319 void setSearchDiscretization(
const std::map<unsigned int, double>& discretization);
324 bool setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices)
override;
328 const std::string& group_name,
const std::string& base_frame,
329 const std::vector<std::string>& tip_frames,
double search_discretization)
override;
335 size_t solve(KDL::Frame& pose_frame,
const std::vector<double>& vfree, IkSolutionList<IkReal>& solutions)
const;
340 void getSolution(
const IkSolutionList<IkReal>& solutions,
int i, std::vector<double>& solution)
const;
345 void getSolution(
const IkSolutionList<IkReal>& solutions,
const std::vector<double>& ik_seed_state,
int i,
346 std::vector<double>& solution)
const;
351 double enforceLimits(
double val,
double min,
double max)
const;
353 void fillFreeParams(
int count,
int* array);
354 bool getCount(
int& count,
const int& max_count,
const int& min_count)
const;
365 bool computeRelativeTransform(
const std::string& from,
const std::string& to, Eigen::Isometry3d& transform,
366 bool& differs_from_identity);
373 void transformToChainFrame(
const geometry_msgs::msg::Pose& ik_pose, KDL::Frame& ik_pose_chain)
const;
376 bool IKFastKinematicsPlugin::computeRelativeTransform(
const std::string& from,
const std::string& to,
377 Eigen::Isometry3d& transform,
bool& differs_from_identity)
379 RobotStatePtr robot_state;
380 robot_state = std::make_shared<RobotState>(robot_model_);
381 robot_state->setToDefaultValues();
384 auto* from_link = robot_model_->getLinkModel(from, &has_link);
385 auto* to_link = robot_model_->getLinkModel(to, &has_link);
386 if (!from_link || !to_link)
389 if (robot_model_->getRigidlyConnectedParentLinkModel(from_link) !=
390 robot_model_->getRigidlyConnectedParentLinkModel(to_link))
392 RCLCPP_ERROR_STREAM(LOGGER,
"Link frames " << from <<
" and " << to <<
" are not rigidly connected.");
396 transform = robot_state->getGlobalLinkTransform(from_link).inverse() * robot_state->getGlobalLinkTransform(to_link);
397 differs_from_identity = !transform.matrix().isIdentity();
401 bool IKFastKinematicsPlugin::initialize(
const rclcpp::Node::SharedPtr& node,
403 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
404 double search_discretization)
406 if (tip_frames.size() != 1)
408 RCLCPP_ERROR(LOGGER,
"Expecting exactly one tip frame.");
412 storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
413 if (!lookupParam(node,
"link_prefix", link_prefix_, std::string(
"")))
415 RCLCPP_INFO(LOGGER,
"Using empty link_prefix.");
419 RCLCPP_INFO_STREAM(LOGGER,
"Using link_prefix: '" << link_prefix_ <<
"'");
424 RCLCPP_ERROR_STREAM(LOGGER,
"tip frame '" << tip_frames_[0] <<
"' does not exist.");
426 RCLCPP_ERROR_STREAM(LOGGER,
"base_frame '" << base_frame_ <<
"' does not exist.");
428 if (!robot_model.
hasLinkModel(link_prefix_ + IKFAST_TIP_FRAME_))
429 RCLCPP_ERROR_STREAM(LOGGER,
"prefixed tip frame '" << link_prefix_ + IKFAST_TIP_FRAME_
430 <<
"' does not exist. "
431 "Please check your link_prefix parameter.");
432 if (!robot_model.
hasLinkModel(link_prefix_ + IKFAST_BASE_FRAME_))
433 RCLCPP_ERROR_STREAM(LOGGER,
"prefixed base frame '" << link_prefix_ + IKFAST_BASE_FRAME_
434 <<
"' does not exist. "
435 "Please check your link_prefix parameter.");
441 if (!computeRelativeTransform(tip_frames_[0], link_prefix_ + IKFAST_TIP_FRAME_, group_tip_to_chain_tip_,
442 tip_transform_required_) ||
443 !computeRelativeTransform(link_prefix_ + IKFAST_BASE_FRAME_, base_frame_, chain_base_to_group_base_,
444 base_transform_required_))
452 if (free_params_.size() > 1)
454 RCLCPP_ERROR(LOGGER,
"Only one free joint parameter supported!");
457 else if (free_params_.size() == 1)
459 redundant_joint_indices_.clear();
460 redundant_joint_indices_.push_back(free_params_[0]);
461 KinematicsBase::setSearchDiscretization(search_discretization);
467 RCLCPP_ERROR_STREAM(LOGGER,
"Unknown planning group: " << group_name);
471 RCLCPP_DEBUG(LOGGER,
"Registering joints and links");
474 while (link && link != base_link)
476 RCLCPP_DEBUG_STREAM(LOGGER,
"Link " << link->
getName());
477 link_names_.push_back(link->
getName());
481 RCLCPP_DEBUG_STREAM(LOGGER,
"Adding joint " << joint->
getName());
483 joint_names_.push_back(joint->
getName());
492 if (joint_names_.size() != num_joints_)
494 RCLCPP_FATAL(LOGGER,
"Joint numbers of RobotModel (%zd) and IKFast solver (%zd) do not match", joint_names_.size(),
499 std::reverse(link_names_.begin(), link_names_.end());
500 std::reverse(joint_names_.begin(), joint_names_.end());
501 std::reverse(joint_min_vector_.begin(), joint_min_vector_.end());
502 std::reverse(joint_max_vector_.begin(), joint_max_vector_.end());
503 std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end());
505 for (
size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
506 RCLCPP_DEBUG_STREAM(LOGGER, joint_names_[joint_id] <<
" " << joint_min_vector_[joint_id] <<
" "
507 << joint_max_vector_[joint_id] <<
" "
508 << joint_has_limits_vector_[joint_id]);
514 void IKFastKinematicsPlugin::setSearchDiscretization(
const std::map<unsigned int, double>& discretization)
516 if (discretization.empty())
518 RCLCPP_ERROR(LOGGER,
"The 'discretization' map is empty");
522 if (redundant_joint_indices_.empty())
524 RCLCPP_ERROR(LOGGER,
"This group's solver doesn't support redundant joints");
528 if (discretization.begin()->first != redundant_joint_indices_[0])
530 std::string redundant_joint = joint_names_[free_params_[0]];
531 RCLCPP_ERROR_STREAM(LOGGER,
"Attempted to discretize a non-redundant joint "
532 << discretization.begin()->first <<
", only joint '" << redundant_joint
533 <<
"' with index " << redundant_joint_indices_[0] <<
" is redundant.");
537 if (discretization.begin()->second <= 0.0)
539 RCLCPP_ERROR_STREAM(LOGGER,
"Discretization can not takes values that are <= 0");
543 redundant_joint_discretization_.clear();
544 redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second;
547 bool IKFastKinematicsPlugin::setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices)
549 RCLCPP_ERROR(LOGGER,
"Changing the redundant joints isn't permitted by this group's solver ");
553 size_t IKFastKinematicsPlugin::solve(KDL::Frame& pose_frame,
const std::vector<double>& vfree,
554 IkSolutionList<IkReal>& solutions)
const
560 trans[0] = pose_frame.p[0];
561 trans[1] = pose_frame.p[1];
562 trans[2] = pose_frame.p[2];
565 KDL::Vector direction;
576 vals[0] = mult(0, 0);
577 vals[1] = mult(0, 1);
578 vals[2] = mult(0, 2);
579 vals[3] = mult(1, 0);
580 vals[4] = mult(1, 1);
581 vals[5] = mult(1, 2);
582 vals[6] = mult(2, 0);
583 vals[7] = mult(2, 1);
584 vals[8] = mult(2, 2);
587 ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
588 return solutions.GetNumSolutions();
596 direction = pose_frame.M * KDL::Vector(0, 0, 1);
597 ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
598 return solutions.GetNumSolutions();
603 RCLCPP_ERROR(LOGGER,
"IK for this IkParameterizationType not implemented yet.");
607 ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
608 return solutions.GetNumSolutions();
613 RCLCPP_ERROR(LOGGER,
"IK for this IkParameterizationType not implemented yet.");
621 double roll, pitch, yaw;
625 pose_frame.M.GetRPY(roll, pitch, yaw);
626 ComputeIk(trans, &yaw, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
627 return solutions.GetNumSolutions();
634 pose_frame.M.GetRPY(roll, pitch, yaw);
635 ComputeIk(trans, &roll, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
636 return solutions.GetNumSolutions();
643 pose_frame.M.GetRPY(roll, pitch, yaw);
644 ComputeIk(trans, &pitch, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
645 return solutions.GetNumSolutions();
648 RCLCPP_ERROR(LOGGER,
"Unknown IkParameterizationType! "
649 "Was the solver generated with an incompatible version of Openrave?");
654 void IKFastKinematicsPlugin::getSolution(
const IkSolutionList<IkReal>& solutions,
int i,
655 std::vector<double>& solution)
const
658 solution.resize(num_joints_);
661 const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
662 std::vector<IkReal> vsolfree(sol.GetFree().size());
663 sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] :
nullptr);
665 for (std::size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
667 if (joint_has_limits_vector_[joint_id])
669 solution[joint_id] = enforceLimits(solution[joint_id], joint_min_vector_[joint_id], joint_max_vector_[joint_id]);
674 void IKFastKinematicsPlugin::getSolution(
const IkSolutionList<IkReal>& solutions,
675 const std::vector<double>& ik_seed_state,
int i,
676 std::vector<double>& solution)
const
679 solution.resize(num_joints_);
682 const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
683 std::vector<IkReal> vsolfree(sol.GetFree().size());
684 sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] :
nullptr);
687 for (std::size_t i = 0; i < num_joints_; ++i)
689 if (joint_has_limits_vector_[i])
691 solution[i] = enforceLimits(solution[i], joint_min_vector_[i], joint_max_vector_[i]);
692 double signed_distance = solution[i] - ik_seed_state[i];
693 while (signed_distance > M_PI && solution[i] - 2 * M_PI > (joint_min_vector_[i] -
LIMIT_TOLERANCE))
695 signed_distance -= 2 * M_PI;
696 solution[i] -= 2 * M_PI;
698 while (signed_distance < -M_PI && solution[i] + 2 * M_PI < (joint_max_vector_[i] +
LIMIT_TOLERANCE))
700 signed_distance += 2 * M_PI;
701 solution[i] += 2 * M_PI;
707 double IKFastKinematicsPlugin::enforceLimits(
double joint_value,
double min,
double max)
const
710 while (joint_value > max)
712 joint_value -= 2 * M_PI;
716 while (joint_value < min)
718 joint_value += 2 * M_PI;
723 void IKFastKinematicsPlugin::fillFreeParams(
int count,
int* array)
725 free_params_.clear();
726 for (
int i = 0; i < count; ++i)
727 free_params_.push_back(array[i]);
730 bool IKFastKinematicsPlugin::getCount(
int& count,
const int& max_count,
const int& min_count)
const
734 if (-count >= min_count)
739 else if (count + 1 <= max_count)
751 if (1 - count <= max_count)
756 else if (count - 1 >= min_count)
766 bool IKFastKinematicsPlugin::getPositionFK(
const std::vector<std::string>& link_names,
767 const std::vector<double>& joint_angles,
768 std::vector<geometry_msgs::msg::Pose>& poses)
const
776 RCLCPP_ERROR(LOGGER,
"Can only compute FK for Transform6D IK type!");
781 if (link_names.size() == 0)
783 RCLCPP_WARN_STREAM(LOGGER,
"Link names with nothing");
787 if (link_names.size() != 1 || link_names[0] != getTipFrame())
789 RCLCPP_ERROR(LOGGER,
"Can compute FK for %s only", getTipFrame().c_str());
795 IkReal eerot[9], eetrans[3];
797 if (joint_angles.size() != num_joints_)
799 RCLCPP_ERROR(LOGGER,
"Unexpected number of joint angles");
803 IkReal angles[num_joints_];
804 for (
unsigned char i = 0; i < num_joints_; ++i)
805 angles[i] = joint_angles[i];
810 for (
int i = 0; i < 3; ++i)
811 p_out.p.data[i] = eetrans[i];
813 for (
int i = 0; i < 9; ++i)
814 p_out.M.data[i] = eerot[i];
817 poses[0] = tf2::toMsg(p_out);
822 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
823 const std::vector<double>& ik_seed_state,
double timeout,
824 std::vector<double>& solution,
825 moveit_msgs::msg::MoveItErrorCodes& error_code,
828 std::vector<double> consistency_limits;
829 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution,
IKCallbackFn(), error_code,
833 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
834 const std::vector<double>& ik_seed_state,
double timeout,
835 const std::vector<double>& consistency_limits,
836 std::vector<double>& solution,
837 moveit_msgs::msg::MoveItErrorCodes& error_code,
840 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution,
IKCallbackFn(), error_code,
844 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
845 const std::vector<double>& ik_seed_state,
double timeout,
846 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
847 moveit_msgs::msg::MoveItErrorCodes& error_code,
850 std::vector<double> consistency_limits;
851 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
855 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
856 const std::vector<double>& ik_seed_state,
double timeout,
857 const std::vector<double>& consistency_limits,
858 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
859 moveit_msgs::msg::MoveItErrorCodes& error_code,
866 if (free_params_.size() == 0)
868 RCLCPP_DEBUG_STREAM(LOGGER,
"No need to search since no free params/redundant joints");
870 std::vector<geometry_msgs::msg::Pose> ik_poses(1, ik_pose);
871 std::vector<std::vector<double>> solutions;
874 if (!getPositionIK(ik_poses, ik_seed_state, solutions, kinematic_result,
options))
876 RCLCPP_DEBUG(LOGGER,
"No solution whatsoever");
877 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
882 std::vector<LimitObeyingSol> solutions_obey_limits;
883 for (std::size_t i = 0; i < solutions.size(); ++i)
885 double dist_from_seed = 0.0;
886 for (std::size_t j = 0; j < ik_seed_state.size(); ++j)
888 dist_from_seed += fabs(ik_seed_state[j] - solutions[i][j]);
891 solutions_obey_limits.push_back({ solutions[i], dist_from_seed });
893 std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
896 if (solution_callback)
898 for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i)
900 solution_callback(ik_pose, solutions_obey_limits[i].value, error_code);
901 if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
903 solution = solutions_obey_limits[i].value;
904 RCLCPP_DEBUG(LOGGER,
"Solution passes callback");
909 RCLCPP_DEBUG_STREAM(LOGGER,
"Solution has error code " << error_code.val);
914 solution = solutions_obey_limits[0].value;
915 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
924 RCLCPP_ERROR(LOGGER,
"Kinematics not active");
925 error_code.val = error_code.NO_IK_SOLUTION;
929 if (ik_seed_state.size() != num_joints_)
931 RCLCPP_ERROR_STREAM(LOGGER,
932 "Seed state must have size " << num_joints_ <<
" instead of size " << ik_seed_state.size());
933 error_code.val = error_code.NO_IK_SOLUTION;
937 if (!consistency_limits.empty() && consistency_limits.size() != num_joints_)
939 RCLCPP_ERROR_STREAM(LOGGER,
"Consistency limits be empty or must have size " << num_joints_ <<
" instead of size "
940 << consistency_limits.size());
941 error_code.val = error_code.NO_IK_SOLUTION;
949 transformToChainFrame(ik_pose, frame);
951 std::vector<double> vfree(free_params_.size());
955 double initial_guess = ik_seed_state[free_params_[0]];
956 vfree[0] = initial_guess;
960 int num_positive_increments;
961 int num_negative_increments;
962 double search_discretization = redundant_joint_discretization_.at(free_params_[0]);
964 if (!consistency_limits.empty())
968 double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess + consistency_limits[free_params_[0]]);
969 double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess - consistency_limits[free_params_[0]]);
971 num_positive_increments =
static_cast<int>((max_limit - initial_guess) / search_discretization);
972 num_negative_increments =
static_cast<int>((initial_guess - min_limit) / search_discretization);
976 num_positive_increments = (joint_max_vector_[free_params_[0]] - initial_guess) / search_discretization;
977 num_negative_increments = (initial_guess - joint_min_vector_[free_params_[0]]) / search_discretization;
983 RCLCPP_DEBUG_STREAM(LOGGER,
"Free param is " << free_params_[0] <<
" initial guess is " << initial_guess
984 <<
", # positive increments: " << num_positive_increments
985 <<
", # negative increments: " << num_negative_increments);
986 if ((search_mode &
OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000)
987 RCLCPP_WARN_STREAM_ONCE(LOGGER,
"Large search space, consider increasing the search discretization");
989 double best_costs = -1.0;
990 std::vector<double> best_solution;
991 int nattempts = 0, nvalid = 0;
995 IkSolutionList<IkReal> solutions;
996 size_t numsol = solve(frame, vfree, solutions);
998 RCLCPP_DEBUG_STREAM(LOGGER,
"Found " << numsol <<
" solutions from IKFast");
1002 for (
size_t s = 0; s < numsol; ++s)
1005 std::vector<double> sol;
1006 getSolution(solutions, ik_seed_state, s, sol);
1008 bool obeys_limits =
true;
1009 for (
size_t i = 0; i < sol.size(); ++i)
1011 if (joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
1013 obeys_limits =
false;
1021 getSolution(solutions, ik_seed_state, s, solution);
1024 if (solution_callback)
1026 solution_callback(ik_pose, solution, error_code);
1030 error_code.val = error_code.SUCCESS;
1033 if (error_code.val == error_code.SUCCESS)
1040 for (
unsigned int i = 0; i < solution.size(); ++i)
1042 double d = fabs(ik_seed_state[i] - solution[i]);
1046 if (costs < best_costs || best_costs == -1.0)
1049 best_solution = solution;
1060 if (!getCount(counter, num_positive_increments, -num_negative_increments))
1063 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
1067 vfree[0] = initial_guess + search_discretization * counter;
1071 RCLCPP_DEBUG_STREAM(LOGGER,
"Valid solutions: " << nvalid <<
"/" << nattempts);
1075 solution = best_solution;
1076 error_code.val = error_code.SUCCESS;
1081 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
1086 bool IKFastKinematicsPlugin::getPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
1087 const std::vector<double>& ik_seed_state, std::vector<double>& solution,
1088 moveit_msgs::msg::MoveItErrorCodes& error_code,
1091 RCLCPP_DEBUG_STREAM(LOGGER,
"getPositionIK");
1095 RCLCPP_ERROR(LOGGER,
"kinematics not active");
1099 if (ik_seed_state.size() < num_joints_)
1101 RCLCPP_ERROR_STREAM(LOGGER,
"ik_seed_state only has " << ik_seed_state.size()
1102 <<
" entries, this ikfast solver requires " << num_joints_);
1107 for (std::size_t i = 0; i < ik_seed_state.size(); ++i)
1110 if (joint_has_limits_vector_[i] && ((ik_seed_state[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
1113 RCLCPP_DEBUG_STREAM(LOGGER,
"IK seed not in limits! " <<
static_cast<int>(i) <<
" value " << ik_seed_state[i]
1114 <<
" has limit: " << joint_has_limits_vector_[i]
1115 <<
" being " << joint_min_vector_[i] <<
" to "
1116 << joint_max_vector_[i]);
1121 std::vector<double> vfree(free_params_.size());
1122 for (std::size_t i = 0; i < free_params_.size(); ++i)
1124 int p = free_params_[i];
1125 RCLCPP_ERROR(LOGGER,
"%u is %f",
p, ik_seed_state[
p]);
1126 vfree[i] = ik_seed_state[
p];
1130 transformToChainFrame(ik_pose, frame);
1132 IkSolutionList<IkReal> solutions;
1133 size_t numsol = solve(frame, vfree, solutions);
1134 RCLCPP_DEBUG_STREAM(LOGGER,
"Found " << numsol <<
" solutions from IKFast");
1136 std::vector<LimitObeyingSol> solutions_obey_limits;
1140 std::vector<double> solution_obey_limits;
1141 for (std::size_t s = 0; s < numsol; ++s)
1143 std::vector<double> sol;
1144 getSolution(solutions, ik_seed_state, s, sol);
1145 RCLCPP_DEBUG(LOGGER,
"Sol %d: %e %e %e %e %e %e",
static_cast<int>(s), sol[0], sol[1], sol[2], sol[3],
1148 bool obeys_limits =
true;
1149 for (std::size_t i = 0; i < sol.size(); ++i)
1152 if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
1156 obeys_limits =
false;
1157 RCLCPP_DEBUG_STREAM(LOGGER,
"Not in limits! " <<
static_cast<int>(i) <<
" value " << sol[i]
1158 <<
" has limit: " << joint_has_limits_vector_[i] <<
" being "
1159 << joint_min_vector_[i] <<
" to " << joint_max_vector_[i]);
1166 getSolution(solutions, ik_seed_state, s, solution_obey_limits);
1167 double dist_from_seed = 0.0;
1168 for (std::size_t i = 0; i < ik_seed_state.size(); ++i)
1170 dist_from_seed += fabs(ik_seed_state[i] - solution_obey_limits[i]);
1173 solutions_obey_limits.push_back({ solution_obey_limits, dist_from_seed });
1179 RCLCPP_DEBUG(LOGGER,
"No IK solution");
1183 if (!solutions_obey_limits.empty())
1185 std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
1186 solution = solutions_obey_limits[0].value;
1187 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
1191 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
1195 bool IKFastKinematicsPlugin::getPositionIK(
const std::vector<geometry_msgs::msg::Pose>& ik_poses,
1196 const std::vector<double>& ik_seed_state,
1197 std::vector<std::vector<double>>& solutions,
1201 RCLCPP_DEBUG_STREAM(LOGGER,
"getPositionIK with multiple solutions");
1205 RCLCPP_ERROR(LOGGER,
"kinematics not active");
1210 if (ik_poses.empty())
1212 RCLCPP_ERROR(LOGGER,
"ik_poses is empty");
1217 if (ik_poses.size() > 1)
1219 RCLCPP_ERROR(LOGGER,
"ik_poses contains multiple entries, only one is allowed");
1224 if (ik_seed_state.size() < num_joints_)
1226 RCLCPP_ERROR_STREAM(LOGGER,
"ik_seed_state only has " << ik_seed_state.size()
1227 <<
" entries, this ikfast solver requires " << num_joints_);
1232 transformToChainFrame(ik_poses[0], frame);
1235 std::vector<IkSolutionList<IkReal>> solution_set;
1236 IkSolutionList<IkReal> ik_solutions;
1237 std::vector<double> vfree;
1239 std::vector<double> sampled_joint_vals;
1240 if (!redundant_joint_indices_.empty())
1243 sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]);
1247 joint_has_limits_vector_[redundant_joint_indices_.front()])
1249 double joint_min = joint_min_vector_[redundant_joint_indices_.front()];
1250 double joint_max = joint_max_vector_[redundant_joint_indices_.front()];
1252 double jv = sampled_joint_vals[0];
1256 RCLCPP_ERROR_STREAM(LOGGER,
"ik seed is out of bounds");
1262 if (!sampleRedundantJoint(
options.discretization_method, sampled_joint_vals))
1268 for (
unsigned int i = 0; i < sampled_joint_vals.size(); ++i)
1271 vfree.push_back(sampled_joint_vals[i]);
1272 numsol += solve(frame, vfree, ik_solutions);
1273 solution_set.push_back(ik_solutions);
1279 numsol = solve(frame, vfree, ik_solutions);
1280 solution_set.push_back(ik_solutions);
1283 RCLCPP_DEBUG_STREAM(LOGGER,
"Found " << numsol <<
" solutions from IKFast");
1284 bool solutions_found =
false;
1290 for (
unsigned int r = 0;
r < solution_set.size(); ++
r)
1292 ik_solutions = solution_set[
r];
1293 numsol = ik_solutions.GetNumSolutions();
1294 for (
int s = 0; s < numsol; ++s)
1296 std::vector<double> sol;
1297 getSolution(ik_solutions, ik_seed_state, s, sol);
1299 bool obeys_limits =
true;
1300 for (
unsigned int i = 0; i < sol.size(); ++i)
1303 if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
1307 obeys_limits =
false;
1308 RCLCPP_DEBUG_STREAM(LOGGER,
"Not in limits! "
1309 << i <<
" value " << sol[i] <<
" has limit: " << joint_has_limits_vector_[i]
1310 <<
" being " << joint_min_vector_[i] <<
" to " << joint_max_vector_[i]);
1317 solutions_found =
true;
1318 solutions.push_back(sol);
1323 if (solutions_found)
1331 RCLCPP_DEBUG_STREAM(LOGGER,
"No IK solution");
1339 std::vector<double>& sampled_joint_vals)
const
1341 int index = redundant_joint_indices_.front();
1342 double joint_dscrt = redundant_joint_discretization_.at(index);
1343 double joint_min = joint_min_vector_[index];
1344 double joint_max = joint_max_vector_[index];
1350 size_t steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1351 for (
size_t i = 0; i < steps; ++i)
1353 sampled_joint_vals.push_back(joint_min + joint_dscrt * i);
1355 sampled_joint_vals.push_back(joint_max);
1360 int steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1361 steps = steps > 0 ? steps : 1;
1362 double diff = joint_max - joint_min;
1363 for (
int i = 0; i < steps; ++i)
1365 sampled_joint_vals.push_back(((diff * std::rand()) / (
static_cast<double>(RAND_MAX))) + joint_min);
1374 RCLCPP_ERROR_STREAM(LOGGER,
"Discretization method " << method <<
" is not supported");
1381 void IKFastKinematicsPlugin::transformToChainFrame(
const geometry_msgs::msg::Pose& ik_pose,
1382 KDL::Frame& ik_pose_chain)
const
1384 if (tip_transform_required_ || base_transform_required_)
1386 Eigen::Isometry3d ik_eigen_pose;
1387 tf2::fromMsg(ik_pose, ik_eigen_pose);
1388 if (tip_transform_required_)
1389 ik_eigen_pose = ik_eigen_pose * group_tip_to_chain_tip_;
1391 if (base_transform_required_)
1392 ik_eigen_pose = chain_base_to_group_base_ * ik_eigen_pose;
1394 tf2::fromMsg(tf2::toMsg(ik_eigen_pose), ik_pose_chain);
1398 tf2::fromMsg(ik_pose, ik_pose_chain);
1405 #include <pluginlib/class_list_macros.hpp>
Provides an interface for kinematics solvers.
std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
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.
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
const std::string & getName() const
The name of this link.
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 of a kinematic model. This class is not thread safe, however multiple instances can be cre...
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_TranslationZAxisAngle4DVelocity
@ IKP_TranslationXAxisAngle4D
@ IKP_Direction3D
direction on end effector coordinate system reaches desired direction
@ IKP_TranslationYAxisAngleXNorm4DVelocity
@ IKP_Direction3DVelocity
@ IKP_TranslationZAxisAngleYNorm4DVelocity
@ 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_TranslationZAxisAngleYNorm4D
@ 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_TranslationLocalGlobal6DVelocity
@ IKP_TranslationXYOrientation3DVelocity
@ IKP_TranslationYAxisAngle4D
@ IKP_TranslationXAxisAngleZNorm4DVelocity
@ IKP_Translation3DVelocity
@ IKP_TranslationYAxisAngle4DVelocity
@ IKP_TranslationXY2D
2D translation along XY plane
@ IKP_TranslationZAxisAngle4D
@ IKP_TranslationDirection5DVelocity
@ IKP_Rotation3D
end effector reaches desired 3D rotation
@ IKP_Transform6DVelocity
@ IKP_TranslationXY2DVelocity
@ IKP_TranslationXYOrientation3D
@ IKP_TranslationXAxisAngleZNorm4D
@ IKP_Lookat3D
direction on end effector coordinate system points to desired 3D position
@ IKP_TranslationYAxisAngleXNorm4D
@ IKP_TranslationXAxisAngle4DVelocity
@ IKP_TranslationDirection5D
@ MULTIPLE_TIPS_NOT_SUPPORTED
@ UNSUPORTED_DISCRETIZATION_REQUESTED
Core components of MoveIt.
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()
std::vector< double > value
bool operator<(const LimitObeyingSol &a) const
A set of options for the kinematics solver.
KinematicError kinematic_error