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>
70 #define IKFAST_NO_MAIN
156 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"ikfast");
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_;
172 std::shared_ptr<prbt_ikfast_kinematics::ParamListener> param_listener_;
173 prbt_ikfast_kinematics::Params params_;
177 const std::string IKFAST_TIP_FRAME_ =
"flange";
178 const std::string IKFAST_BASE_FRAME_ =
"base_link";
184 bool tip_transform_required_;
185 bool base_transform_required_;
189 Eigen::Isometry3d chain_base_to_group_base_;
190 Eigen::Isometry3d group_tip_to_chain_tip_;
194 const std::vector<std::string>& getJointNames()
const override
198 const std::vector<std::string>& getLinkNames()
const override
209 srand(time(
nullptr));
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,
245 bool getPositionIK(
const std::vector<geometry_msgs::msg::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
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,
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,
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,
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,
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;
326 void setSearchDiscretization(
const std::map<unsigned int, double>& discretization);
331 bool setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices)
override;
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;
342 size_t solve(KDL::Frame& pose_frame,
const std::vector<double>& vfree,
IkSolutionList<IkReal>& solutions)
const;
352 void getSolution(
const IkSolutionList<IkReal>& solutions,
const std::vector<double>& ik_seed_state,
int i,
353 std::vector<double>& solution)
const;
358 double enforceLimits(
double val,
double min,
double max)
const;
360 void fillFreeParams(
int count,
int* array);
361 bool getCount(
int& count,
int max_count,
int min_count)
const;
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;
383 bool IKFastKinematicsPlugin::computeRelativeTransform(
const std::string& from,
const std::string& to,
384 Eigen::Isometry3d& transform,
bool& differs_from_identity)
386 RobotStatePtr robot_state = std::make_shared<RobotState>(robot_model_);
387 robot_state->setToDefaultValues();
389 auto* from_link = robot_model_->getLinkModel(from);
390 auto* to_link = robot_model_->getLinkModel(to);
391 if (!from_link || !to_link)
394 if (robot_model_->getRigidlyConnectedParentLinkModel(from_link) !=
395 robot_model_->getRigidlyConnectedParentLinkModel(to_link))
397 RCLCPP_ERROR_STREAM(LOGGER,
"Link frames " << from <<
" and " << to <<
" are not rigidly connected.");
401 transform = robot_state->getGlobalLinkTransform(from_link).inverse() * robot_state->getGlobalLinkTransform(to_link);
402 differs_from_identity = !transform.matrix().isIdentity();
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)
410 if (tip_frames.size() != 1)
412 RCLCPP_ERROR(LOGGER,
"Expecting exactly one tip frame.");
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();
420 storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
422 RCLCPP_INFO_STREAM(LOGGER,
"Using link_prefix: '" << params_.link_prefix <<
'\'');
426 RCLCPP_ERROR_STREAM(LOGGER,
"tip frame '" << tip_frames_[0] <<
"' does not exist.");
428 RCLCPP_ERROR_STREAM(LOGGER,
"base_frame '" << base_frame_ <<
"' does not exist.");
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.");
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.");
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_))
456 if (free_params_.size() > 1)
458 RCLCPP_ERROR(LOGGER,
"Only one free joint parameter supported!");
461 else if (free_params_.size() == 1)
463 redundant_joint_indices_.clear();
464 redundant_joint_indices_.push_back(free_params_[0]);
465 KinematicsBase::setSearchDiscretization(search_discretization);
471 RCLCPP_ERROR_STREAM(LOGGER,
"Unknown planning group: " << group_name);
475 RCLCPP_DEBUG_STREAM(LOGGER,
"Registering joints and links");
478 while (link && link != base_link)
480 RCLCPP_DEBUG_STREAM(LOGGER,
"Link " << link->
getName());
481 link_names_.push_back(link->
getName());
485 RCLCPP_DEBUG_STREAM(LOGGER,
"Adding joint " << joint->
getName());
487 joint_names_.push_back(joint->
getName());
496 if (joint_names_.size() != num_joints_)
498 RCLCPP_FATAL(LOGGER,
"Joint numbers of RobotModel (%zd) and IKFast solver (%zd) do not match", joint_names_.size(),
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());
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]);
519 void IKFastKinematicsPlugin::setSearchDiscretization(
const std::map<unsigned int, double>& discretization)
521 if (discretization.empty())
523 RCLCPP_ERROR(LOGGER,
"The 'discretization' map is empty");
527 if (redundant_joint_indices_.empty())
529 RCLCPP_ERROR_STREAM(LOGGER,
"This group's solver doesn't support redundant joints");
533 if (discretization.begin()->first != redundant_joint_indices_[0])
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.");
542 if (discretization.begin()->second <= 0.0)
544 RCLCPP_ERROR_STREAM(LOGGER,
"Discretization can not takes values that are <= 0");
548 redundant_joint_discretization_.clear();
549 redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second;
552 bool IKFastKinematicsPlugin::setRedundantJoints(
const std::vector<unsigned int>& )
554 RCLCPP_ERROR_STREAM(LOGGER,
"Changing the redundant joints isn't permitted by this group's solver ");
558 size_t IKFastKinematicsPlugin::solve(KDL::Frame& pose_frame,
const std::vector<double>& vfree,
565 trans[0] = pose_frame.p[0];
566 trans[1] = pose_frame.p[1];
567 trans[2] = pose_frame.p[2];
570 KDL::Vector direction;
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);
592 ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
601 direction = pose_frame.M * KDL::Vector(0, 0, 1);
602 ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
611 RCLCPP_ERROR(LOGGER,
"IK for this IkParameterizationType not implemented yet.");
617 RCLCPP_ERROR(LOGGER,
"IK for this IkParameterizationType not implemented yet.");
624 RCLCPP_ERROR(LOGGER,
"IK for this IkParameterizationType not implemented yet.");
628 double roll, pitch, yaw;
632 pose_frame.M.GetRPY(roll, pitch, yaw);
633 ComputeIk(trans, &yaw, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
640 pose_frame.M.GetRPY(roll, pitch, yaw);
641 ComputeIk(trans, &roll, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
648 pose_frame.M.GetRPY(roll, pitch, yaw);
649 ComputeIk(trans, &pitch, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
653 RCLCPP_ERROR(LOGGER,
"Unknown IkParameterizationType! "
654 "Was the solver generated with an incompatible version of Openrave?");
660 std::vector<double>& solution)
const
663 solution.resize(num_joints_);
667 std::vector<IkReal> vsolfree(sol.
GetFree().size());
668 sol.
GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] :
nullptr);
670 for (std::size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
672 if (joint_has_limits_vector_[joint_id])
674 solution[joint_id] = enforceLimits(solution[joint_id], joint_min_vector_[joint_id], joint_max_vector_[joint_id]);
680 const std::vector<double>& ik_seed_state,
int i,
681 std::vector<double>& solution)
const
684 solution.resize(num_joints_);
688 std::vector<IkReal> vsolfree(sol.
GetFree().size());
689 sol.
GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] :
nullptr);
692 for (std::size_t i = 0; i < num_joints_; ++i)
694 if (joint_has_limits_vector_[i])
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))
700 signed_distance -= 2 * M_PI;
701 solution[i] -= 2 * M_PI;
703 while (signed_distance < -M_PI && solution[i] + 2 * M_PI < (joint_max_vector_[i] +
LIMIT_TOLERANCE))
705 signed_distance += 2 * M_PI;
706 solution[i] += 2 * M_PI;
712 double IKFastKinematicsPlugin::enforceLimits(
double joint_value,
double min,
double max)
const
715 while (joint_value > max)
717 joint_value -= 2 * M_PI;
721 while (joint_value < min)
723 joint_value += 2 * M_PI;
728 void IKFastKinematicsPlugin::fillFreeParams(
int count,
int* array)
730 free_params_.clear();
731 for (
int i = 0; i < count; ++i)
732 free_params_.push_back(array[i]);
735 bool IKFastKinematicsPlugin::getCount(
int& count,
int max_count,
int min_count)
const
739 if (-count >= min_count)
744 else if (count + 1 <= max_count)
756 if (1 - count <= max_count)
761 else if (count - 1 >= min_count)
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
781 RCLCPP_ERROR(LOGGER,
"Can only compute FK for Transform6D IK type!");
786 if (link_names.size() == 0)
788 RCLCPP_WARN_STREAM(LOGGER,
"Link names with nothing");
792 if (link_names.size() != 1 || link_names[0] != getTipFrame())
794 RCLCPP_ERROR(LOGGER,
"Can compute FK for %s only", getTipFrame().c_str());
800 IkReal eerot[9], eetrans[3];
802 if (joint_angles.size() != num_joints_)
804 RCLCPP_ERROR(LOGGER,
"Unexpected number of joint angles");
808 std::vector<IkReal> angles(num_joints_, 0);
809 for (
unsigned char i = 0; i < num_joints_; i++)
810 angles[i] = joint_angles[i];
813 ComputeFk(angles.data(), eetrans, eerot);
815 for (
int i = 0; i < 3; ++i)
816 p_out.p.data[i] = eetrans[i];
818 for (
int i = 0; i < 9; ++i)
819 p_out.M.data[i] = eerot[i];
822 poses[0] = tf2::toMsg(p_out);
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,
832 std::vector<double> consistency_limits;
833 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution,
IKCallbackFn(), error_code,
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,
843 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution,
IKCallbackFn(), error_code,
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,
853 std::vector<double> consistency_limits;
854 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
858 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
859 const std::vector<double>& ik_seed_state,
double ,
860 const std::vector<double>& consistency_limits,
861 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
862 moveit_msgs::msg::MoveItErrorCodes& error_code,
869 if (free_params_.size() == 0)
871 RCLCPP_DEBUG_STREAM(LOGGER,
"No need to search since no free params/redundant joints");
873 std::vector<geometry_msgs::msg::Pose> ik_poses(1, ik_pose);
874 std::vector<std::vector<double>> solutions;
877 if (!getPositionIK(ik_poses, ik_seed_state, solutions, kinematic_result,
options))
879 RCLCPP_DEBUG_STREAM(LOGGER,
"No solution whatsoever");
880 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
885 std::vector<LimitObeyingSol> solutions_obey_limits;
886 for (std::size_t i = 0; i < solutions.size(); ++i)
888 double dist_from_seed = 0.0;
889 for (std::size_t j = 0; j < ik_seed_state.size(); ++j)
891 dist_from_seed += fabs(ik_seed_state[j] - solutions[i][j]);
894 solutions_obey_limits.push_back({ solutions[i], dist_from_seed });
896 std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
899 if (solution_callback)
901 for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i)
903 solution_callback(ik_pose, solutions_obey_limits[i].value, error_code);
904 if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
906 solution = solutions_obey_limits[i].value;
907 RCLCPP_DEBUG_STREAM(LOGGER,
"Solution passes callback");
912 RCLCPP_DEBUG_STREAM(LOGGER,
"Solution has error code " << error_code.val);
917 solution = solutions_obey_limits[0].value;
918 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
927 RCLCPP_ERROR_STREAM(LOGGER,
"Kinematics not active");
928 error_code.val = error_code.NO_IK_SOLUTION;
932 if (ik_seed_state.size() != num_joints_)
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;
940 if (!consistency_limits.empty() && consistency_limits.size() != num_joints_)
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;
952 transformToChainFrame(ik_pose, frame);
954 std::vector<double> vfree(free_params_.size());
958 double initial_guess = ik_seed_state[free_params_[0]];
959 vfree[0] = initial_guess;
963 int num_positive_increments;
964 int num_negative_increments;
965 double search_discretization = redundant_joint_discretization_.at(free_params_[0]);
967 if (!consistency_limits.empty())
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]]);
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);
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;
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");
992 double best_costs = -1.0;
993 std::vector<double> best_solution;
994 int nattempts = 0, nvalid = 0;
999 size_t numsol = solve(frame, vfree, solutions);
1001 RCLCPP_DEBUG_STREAM(LOGGER,
"Found " << numsol <<
" solutions from IKFast");
1005 for (
size_t s = 0; s < numsol; ++s)
1008 std::vector<double> sol;
1009 getSolution(solutions, ik_seed_state, s, sol);
1011 bool obeys_limits =
true;
1012 for (
size_t i = 0; i < sol.size(); i++)
1014 if (joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
1016 obeys_limits =
false;
1024 getSolution(solutions, ik_seed_state, s, solution);
1027 if (solution_callback)
1029 solution_callback(ik_pose, solution, error_code);
1033 error_code.val = error_code.SUCCESS;
1036 if (error_code.val == error_code.SUCCESS)
1043 for (
unsigned int i = 0; i < solution.size(); i++)
1045 double d = fabs(ik_seed_state[i] - solution[i]);
1049 if (costs < best_costs || best_costs == -1.0)
1052 best_solution = solution;
1064 if (!getCount(counter, num_positive_increments, -num_negative_increments))
1067 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
1071 vfree[0] = initial_guess + search_discretization * counter;
1075 RCLCPP_DEBUG_STREAM(LOGGER,
"Valid solutions: " << nvalid <<
'/' << nattempts);
1079 solution = best_solution;
1080 error_code.val = error_code.SUCCESS;
1085 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
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,
1094 RCLCPP_DEBUG_STREAM(LOGGER,
"getPositionIK");
1098 RCLCPP_ERROR(LOGGER,
"kinematics not active");
1102 if (ik_seed_state.size() < num_joints_)
1104 RCLCPP_ERROR_STREAM(LOGGER,
"ik_seed_state only has " << ik_seed_state.size()
1105 <<
" entries, this ikfast solver requires " << num_joints_);
1110 for (std::size_t i = 0; i < ik_seed_state.size(); i++)
1113 if (joint_has_limits_vector_[i] && ((ik_seed_state[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
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]);
1123 std::vector<double> vfree(free_params_.size());
1124 for (std::size_t i = 0; i < free_params_.size(); ++i)
1126 int p = free_params_[i];
1127 RCLCPP_ERROR(LOGGER,
"%u is %f", p, ik_seed_state[p]);
1128 vfree[i] = ik_seed_state[p];
1132 transformToChainFrame(ik_pose, frame);
1135 size_t numsol = solve(frame, vfree, solutions);
1136 RCLCPP_DEBUG_STREAM(LOGGER,
"Found " << numsol <<
" solutions from IKFast");
1138 std::vector<LimitObeyingSol> solutions_obey_limits;
1142 std::vector<double> solution_obey_limits;
1143 for (std::size_t s = 0; s < numsol; ++s)
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],
1150 bool obeys_limits =
true;
1151 for (std::size_t i = 0; i < sol.size(); i++)
1154 if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
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]);
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)
1172 dist_from_seed += fabs(ik_seed_state[i] - solution_obey_limits[i]);
1175 solutions_obey_limits.push_back({ solution_obey_limits, dist_from_seed });
1181 RCLCPP_DEBUG_STREAM(LOGGER,
"No IK solution");
1185 if (!solutions_obey_limits.empty())
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;
1193 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
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,
1203 RCLCPP_DEBUG_STREAM(LOGGER,
"getPositionIK with multiple solutions");
1207 RCLCPP_ERROR(LOGGER,
"kinematics not active");
1212 if (ik_poses.empty())
1214 RCLCPP_ERROR(LOGGER,
"ik_poses is empty");
1219 if (ik_poses.size() > 1)
1221 RCLCPP_ERROR(LOGGER,
"ik_poses contains multiple entries, only one is allowed");
1226 if (ik_seed_state.size() < num_joints_)
1228 RCLCPP_ERROR_STREAM(LOGGER,
"ik_seed_state only has " << ik_seed_state.size()
1229 <<
" entries, this ikfast solver requires " << num_joints_);
1234 transformToChainFrame(ik_poses[0], frame);
1237 std::vector<IkSolutionList<IkReal>> solution_set;
1239 std::vector<double> vfree;
1241 std::vector<double> sampled_joint_vals;
1242 if (!redundant_joint_indices_.empty())
1245 sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]);
1249 joint_has_limits_vector_[redundant_joint_indices_.front()])
1251 double joint_min = joint_min_vector_[redundant_joint_indices_.front()];
1252 double joint_max = joint_max_vector_[redundant_joint_indices_.front()];
1254 double jv = sampled_joint_vals[0];
1258 RCLCPP_ERROR_STREAM(LOGGER,
"ik seed is out of bounds");
1264 if (!sampleRedundantJoint(
options.discretization_method, sampled_joint_vals))
1270 for (
unsigned int i = 0; i < sampled_joint_vals.size(); i++)
1273 vfree.push_back(sampled_joint_vals[i]);
1274 numsol += solve(frame, vfree, ik_solutions);
1275 solution_set.push_back(ik_solutions);
1281 numsol = solve(frame, vfree, ik_solutions);
1282 solution_set.push_back(ik_solutions);
1285 RCLCPP_DEBUG_STREAM(LOGGER,
"Found " << numsol <<
" solutions from IKFast");
1286 bool solutions_found =
false;
1292 for (
unsigned int r = 0; r < solution_set.size(); r++)
1294 ik_solutions = solution_set[r];
1296 for (
int s = 0; s < numsol; ++s)
1298 std::vector<double> sol;
1299 getSolution(ik_solutions, ik_seed_state, s, sol);
1301 bool obeys_limits =
true;
1302 for (
unsigned int i = 0; i < sol.size(); i++)
1305 if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
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]);
1319 solutions_found =
true;
1320 solutions.push_back(sol);
1325 if (solutions_found)
1333 RCLCPP_DEBUG_STREAM(LOGGER,
"No IK solution");
1341 std::vector<double>& sampled_joint_vals)
const
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];
1352 size_t steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1353 for (
size_t i = 0; i < steps; i++)
1355 sampled_joint_vals.push_back(joint_min + joint_dscrt * i);
1357 sampled_joint_vals.push_back(joint_max);
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++)
1367 sampled_joint_vals.push_back(((diff * std::rand()) / (
static_cast<double>(RAND_MAX))) + joint_min);
1376 RCLCPP_ERROR_STREAM(LOGGER,
"Discretization method " << method <<
" is not supported");
1383 void IKFastKinematicsPlugin::transformToChainFrame(
const geometry_msgs::msg::Pose& ik_pose, KDL::Frame& ik_pose_chain)
const
1385 if (tip_transform_required_ || base_transform_required_)
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_;
1392 if (base_transform_required_)
1393 ik_eigen_pose = chain_base_to_group_base_ * ik_eigen_pose;
1395 tf2::transformEigenToKDL(ik_eigen_pose, ik_pose_chain);
1399 tf2::fromMsg(ik_pose, ik_pose_chain);
1406 #include <pluginlib/class_list_macros.hpp>
The discrete solutions are returned in this structure.
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.
virtual const IkSolutionBase< T > & GetSolution(size_t index) const
returns the solution pointer
virtual size_t GetNumSolutions() const
returns the number of solutions stored
virtual void Clear()
clears all current solutions, note that any memory addresses returned from GetSolution will be invali...
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.
SEARCH_MODE
Search modes for searchPositionIK(), see there.
@ MULTIPLE_TIPS_NOT_SUPPORTED
@ UNSUPORTED_DISCRETIZATION_REQUESTED
Core components of MoveIt.
IkParameterizationType
The types of inverse kinematics parameterizations supported.
@ IKP_Direction3D
direction on end effector coordinate system reaches desired direction
@ IKP_TranslationZAxisAngle4DVelocity
@ IKP_TranslationXAxisAngleZNorm4DVelocity
@ IKP_UniqueIdMask
the mask for the unique ids
@ IKP_TranslationDirection5DVelocity
@ IKP_TranslationXY2D
2D translation along XY plane
@ IKP_Transform6DVelocity
@ 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_Translation3DVelocity
@ IKP_TranslationYAxisAngleXNorm4D
@ IKP_TranslationLocalGlobal6DVelocity
@ IKP_TranslationDirection5D
@ IKP_TranslationXAxisAngle4D
@ IKP_TranslationZAxisAngleYNorm4DVelocity
@ IKP_TranslationYAxisAngle4DVelocity
@ IKP_TranslationXAxisAngle4DVelocity
@ 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_TranslationZAxisAngle4D
@ IKP_Transform6D
end effector reaches desired 6D transformation
@ IKP_TranslationXAxisAngleZNorm4D
@ IKP_TranslationXYOrientation3DVelocity
@ IKP_TranslationXYOrientation3D
@ IKP_Lookat3D
direction on end effector coordinate system points to desired 3D position
@ IKP_TranslationYAxisAngleXNorm4DVelocity
@ IKP_TranslationXY2DVelocity
@ IKP_TranslationYAxisAngle4D
@ IKP_TranslationZAxisAngleYNorm4D
@ IKP_Direction3DVelocity
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.
KinematicError kinematic_error
std::vector< double > value
bool operator<(const LimitObeyingSol &a) const