47 #include <Eigen/Geometry> 65 #define IKFAST_NO_MAIN // Don't include main() from IKFast 162 std::vector<int> free_params_;
166 const std::string IKFAST_TIP_FRAME_ =
"wrist_roll_link";
167 const std::string IKFAST_BASE_FRAME_ =
"torso_lift_link";
173 bool tip_transform_required_;
174 bool base_transform_required_;
182 const std::string name_{
"ikfast" };
199 srand(time(
nullptr));
216 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state, std::vector<double>& solution,
217 moveit_msgs::MoveItErrorCodes& error_code,
235 bool getPositionIK(
const std::vector<geometry_msgs::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
247 bool searchPositionIK(
248 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
249 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
261 bool searchPositionIK(
262 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
263 const std::vector<double>& consistency_limits, std::vector<double>& solution,
264 moveit_msgs::MoveItErrorCodes& error_code,
275 bool searchPositionIK(
276 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
277 std::vector<double>& solution,
const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
290 bool searchPositionIK(
291 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
292 const std::vector<double>& consistency_limits, std::vector<double>& solution,
293 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
304 bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
305 std::vector<geometry_msgs::Pose>& poses)
const override;
316 void setSearchDiscretization(
const std::map<unsigned int, double>& discretization);
321 bool setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices)
override;
325 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
326 double search_discretization)
override;
342 void getSolution(
const IkSolutionList<IkReal>& solutions,
const std::vector<double>& ik_seed_state,
int i,
343 std::vector<double>& solution)
const;
348 double enforceLimits(
double val,
double min,
double max)
const;
350 void fillFreeParams(
int count,
int* array);
351 bool getCount(
int& count,
const int& max_count,
const int& min_count)
const;
362 bool computeRelativeTransform(
const std::string& from,
const std::string& to, Eigen::Isometry3d& transform,
363 bool& differs_from_identity);
370 void transformToChainFrame(
const geometry_msgs::Pose& ik_pose,
KDL::Frame& ik_pose_chain)
const;
373 bool IKFastKinematicsPlugin::computeRelativeTransform(
const std::string& from,
const std::string& to,
374 Eigen::Isometry3d& transform,
bool& differs_from_identity)
376 RobotStatePtr robot_state;
379 auto* from_link = robot_state->getLinkModel(from);
380 auto* to_link = robot_state->getLinkModel(to);
385 if (!from_link || !to_link)
388 if (robot_state->getRobotModel()->getRigidlyConnectedParentLinkModel(from_link) !=
389 robot_state->getRobotModel()->getRigidlyConnectedParentLinkModel(to_link))
395 transform = robot_state->getGlobalLinkTransform(from_link).inverse() * robot_state->getGlobalLinkTransform(to_link);
396 differs_from_identity = !transform.matrix().isIdentity();
401 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
402 double search_discretization)
404 if (tip_frames.size() != 1)
410 storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
417 if (!computeRelativeTransform(tip_frames_[0], IKFAST_TIP_FRAME_, group_tip_to_chain_tip_, tip_transform_required_) ||
418 !computeRelativeTransform(IKFAST_BASE_FRAME_, base_frame_, chain_base_to_group_base_, base_transform_required_))
424 if (free_params_.size() > 1)
429 else if (free_params_.size() == 1)
431 redundant_joint_indices_.clear();
432 redundant_joint_indices_.push_back(free_params_[0]);
433 KinematicsBase::setSearchDiscretization(search_discretization);
446 while (link && link != base_link)
449 link_names_.push_back(link->
getName());
455 joint_names_.push_back(joint->
getName());
464 if (joint_names_.size() != num_joints_)
466 ROS_FATAL_NAMED(name_,
"Joint numbers of RobotModel (%zd) and IKFast solver (%zd) do not match",
467 joint_names_.size(), num_joints_);
471 std::reverse(link_names_.begin(), link_names_.end());
472 std::reverse(joint_names_.begin(), joint_names_.end());
473 std::reverse(joint_min_vector_.begin(), joint_min_vector_.end());
474 std::reverse(joint_max_vector_.begin(), joint_max_vector_.end());
475 std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end());
477 for (
size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
479 << joint_max_vector_[joint_id] <<
" " 480 << joint_has_limits_vector_[joint_id]);
486 void IKFastKinematicsPlugin::setSearchDiscretization(
const std::map<unsigned int, double>& discretization)
488 if (discretization.empty())
490 ROS_ERROR(
"The 'discretization' map is empty");
494 if (redundant_joint_indices_.empty())
500 if (discretization.begin()->first != redundant_joint_indices_[0])
502 std::string redundant_joint = joint_names_[free_params_[0]];
504 << discretization.begin()->first <<
", only joint '" << redundant_joint
505 <<
"' with index " << redundant_joint_indices_[0] <<
" is redundant.");
509 if (discretization.begin()->second <= 0.0)
515 redundant_joint_discretization_.clear();
516 redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second;
519 bool IKFastKinematicsPlugin::setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices)
525 size_t IKFastKinematicsPlugin::solve(
KDL::Frame& pose_frame,
const std::vector<double>& vfree,
532 trans[0] = pose_frame.
p[0];
533 trans[1] = pose_frame.
p[1];
534 trans[2] = pose_frame.
p[2];
548 vals[0] = mult(0, 0);
549 vals[1] = mult(0, 1);
550 vals[2] = mult(0, 2);
551 vals[3] = mult(1, 0);
552 vals[4] = mult(1, 1);
553 vals[5] = mult(1, 2);
554 vals[6] = mult(2, 0);
555 vals[7] = mult(2, 1);
556 vals[8] = mult(2, 2);
559 ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
569 ComputeIk(trans, direction.
data, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
578 ROS_ERROR_NAMED(name_,
"IK for this IkParameterizationType not implemented yet.");
584 ROS_ERROR_NAMED(name_,
"IK for this IkParameterizationType not implemented yet.");
591 ROS_ERROR_NAMED(name_,
"IK for this IkParameterizationType not implemented yet.");
595 double roll, pitch, yaw;
599 pose_frame.
M.
GetRPY(roll, pitch, yaw);
600 ComputeIk(trans, &yaw, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
607 pose_frame.
M.
GetRPY(roll, pitch, yaw);
608 ComputeIk(trans, &roll, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
615 pose_frame.
M.
GetRPY(roll, pitch, yaw);
616 ComputeIk(trans, &pitch, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
621 "Was the solver generated with an incompatible version of Openrave?");
627 std::vector<double>& solution)
const 630 solution.resize(num_joints_);
634 std::vector<IkReal> vsolfree(sol.
GetFree().size());
635 sol.
GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] :
nullptr);
637 for (std::size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
639 if (joint_has_limits_vector_[joint_id])
641 solution[joint_id] = enforceLimits(solution[joint_id], joint_min_vector_[joint_id], joint_max_vector_[joint_id]);
647 const std::vector<double>& ik_seed_state,
int i,
648 std::vector<double>& solution)
const 651 solution.resize(num_joints_);
655 std::vector<IkReal> vsolfree(sol.
GetFree().size());
656 sol.
GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] :
nullptr);
659 for (std::size_t i = 0; i < num_joints_; ++i)
661 if (joint_has_limits_vector_[i])
663 solution[i] = enforceLimits(solution[i], joint_min_vector_[i], joint_max_vector_[i]);
664 double signed_distance = solution[i] - ik_seed_state[i];
667 signed_distance -= 2 *
M_PI;
668 solution[i] -= 2 *
M_PI;
672 signed_distance += 2 *
M_PI;
673 solution[i] += 2 *
M_PI;
679 double IKFastKinematicsPlugin::enforceLimits(
double joint_value,
double min,
double max)
const 682 while (joint_value > max)
684 joint_value -= 2 *
M_PI;
688 while (joint_value < min)
690 joint_value += 2 *
M_PI;
695 void IKFastKinematicsPlugin::fillFreeParams(
int count,
int* array)
697 free_params_.clear();
698 for (
int i = 0; i < count; ++i)
699 free_params_.push_back(array[i]);
702 bool IKFastKinematicsPlugin::getCount(
int& count,
const int& max_count,
const int& min_count)
const 706 if (-count >= min_count)
711 else if (count + 1 <= max_count)
723 if (1 - count <= max_count)
728 else if (count - 1 >= min_count)
738 bool IKFastKinematicsPlugin::getPositionFK(
const std::vector<std::string>& link_names,
739 const std::vector<double>& joint_angles,
740 std::vector<geometry_msgs::Pose>& poses)
const 748 ROS_ERROR_NAMED(name_,
"Can only compute FK for Transform6D IK type!");
753 if (link_names.size() == 0)
759 if (link_names.size() != 1 || link_names[0] != getTipFrame())
761 ROS_ERROR_NAMED(name_,
"Can compute FK for %s only", getTipFrame().c_str());
767 IkReal eerot[9], eetrans[3];
769 if (joint_angles.size() != num_joints_)
775 IkReal angles[num_joints_];
776 for (
unsigned char i = 0; i < num_joints_; i++)
777 angles[i] = joint_angles[i];
782 for (
int i = 0; i < 3; ++i)
783 p_out.
p.
data[i] = eetrans[i];
785 for (
int i = 0; i < 9; ++i)
786 p_out.
M.
data[i] = eerot[i];
794 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose& ik_pose,
795 const std::vector<double>& ik_seed_state,
double timeout,
796 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
799 std::vector<double> consistency_limits;
800 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution,
IKCallbackFn(), error_code,
804 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose& ik_pose,
805 const std::vector<double>& ik_seed_state,
double timeout,
806 const std::vector<double>& consistency_limits,
807 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
810 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution,
IKCallbackFn(), error_code,
814 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose& ik_pose,
815 const std::vector<double>& ik_seed_state,
double timeout,
816 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
817 moveit_msgs::MoveItErrorCodes& error_code,
820 std::vector<double> consistency_limits;
821 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
825 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose& ik_pose,
826 const std::vector<double>& ik_seed_state,
double timeout,
827 const std::vector<double>& consistency_limits,
828 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
829 moveit_msgs::MoveItErrorCodes& error_code,
836 if (free_params_.size() == 0)
840 std::vector<geometry_msgs::Pose> ik_poses(1, ik_pose);
841 std::vector<std::vector<double>> solutions;
844 if (!getPositionIK(ik_poses, ik_seed_state, solutions, kinematic_result, options))
847 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
852 std::vector<LimitObeyingSol> solutions_obey_limits;
853 for (std::size_t i = 0; i < solutions.size(); ++i)
855 double dist_from_seed = 0.0;
856 for (std::size_t j = 0; j < ik_seed_state.size(); ++j)
858 dist_from_seed += fabs(ik_seed_state[j] - solutions[i][j]);
861 solutions_obey_limits.push_back({ solutions[i], dist_from_seed });
863 std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
866 if (!solution_callback.empty())
868 for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i)
870 solution_callback(ik_pose, solutions_obey_limits[i].value, error_code);
871 if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
873 solution = solutions_obey_limits[i].value;
884 solution = solutions_obey_limits[0].value;
885 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
895 error_code.val = error_code.NO_IK_SOLUTION;
899 if (ik_seed_state.size() != num_joints_)
902 << ik_seed_state.size());
903 error_code.val = error_code.NO_IK_SOLUTION;
907 if (!consistency_limits.empty() && consistency_limits.size() != num_joints_)
909 ROS_ERROR_STREAM_NAMED(name_,
"Consistency limits be empty or must have size " << num_joints_ <<
" instead of size " 910 << consistency_limits.size());
911 error_code.val = error_code.NO_IK_SOLUTION;
919 transformToChainFrame(ik_pose, frame);
921 std::vector<double> vfree(free_params_.size());
925 double initial_guess = ik_seed_state[free_params_[0]];
926 vfree[0] = initial_guess;
930 int num_positive_increments;
931 int num_negative_increments;
932 double search_discretization = redundant_joint_discretization_.at(free_params_[0]);
934 if (!consistency_limits.empty())
938 double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess + consistency_limits[free_params_[0]]);
939 double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess - consistency_limits[free_params_[0]]);
941 num_positive_increments =
static_cast<int>((max_limit - initial_guess) / search_discretization);
942 num_negative_increments =
static_cast<int>((initial_guess - min_limit) / search_discretization);
946 num_positive_increments = (joint_max_vector_[free_params_[0]] - initial_guess) / search_discretization;
947 num_negative_increments = (initial_guess - joint_min_vector_[free_params_[0]]) / search_discretization;
953 ROS_DEBUG_STREAM_NAMED(name_,
"Free param is " << free_params_[0] <<
" initial guess is " << initial_guess
954 <<
", # positive increments: " << num_positive_increments
955 <<
", # negative increments: " << num_negative_increments);
956 if ((search_mode &
OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000)
959 double best_costs = -1.0;
960 std::vector<double> best_solution;
961 int nattempts = 0, nvalid = 0;
966 size_t numsol = solve(frame, vfree, solutions);
972 for (
size_t s = 0;
s < numsol; ++
s)
975 std::vector<double> sol;
976 getSolution(solutions, ik_seed_state,
s, sol);
978 bool obeys_limits =
true;
979 for (
size_t i = 0; i < sol.size(); i++)
981 if (joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
983 obeys_limits =
false;
991 getSolution(solutions, ik_seed_state,
s, solution);
994 if (!solution_callback.empty())
996 solution_callback(ik_pose, solution, error_code);
1000 error_code.val = error_code.SUCCESS;
1003 if (error_code.val == error_code.SUCCESS)
1006 if (search_mode & OPTIMIZE_MAX_JOINT)
1010 for (
unsigned int i = 0; i < solution.size(); i++)
1012 double d = fabs(ik_seed_state[i] - solution[i]);
1016 if (costs < best_costs || best_costs == -1.0)
1019 best_solution = solution;
1030 if (!getCount(counter, num_positive_increments, -num_negative_increments))
1033 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1037 vfree[0] = initial_guess + search_discretization * counter;
1043 if ((search_mode & OPTIMIZE_MAX_JOINT) && best_costs != -1.0)
1045 solution = best_solution;
1046 error_code.val = error_code.SUCCESS;
1051 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1056 bool IKFastKinematicsPlugin::getPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
1057 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
1068 if (ik_seed_state.size() < num_joints_)
1071 <<
" entries, this ikfast solver requires " << num_joints_);
1076 for (std::size_t i = 0; i < ik_seed_state.size(); i++)
1079 if (joint_has_limits_vector_[i] && ((ik_seed_state[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
1082 ROS_DEBUG_STREAM_NAMED(name_,
"IK seed not in limits! " << static_cast<int>(i) <<
" value " << ik_seed_state[i]
1083 <<
" has limit: " << joint_has_limits_vector_[i]
1084 <<
" being " << joint_min_vector_[i] <<
" to " 1085 << joint_max_vector_[i]);
1090 std::vector<double> vfree(free_params_.size());
1091 for (std::size_t i = 0; i < free_params_.size(); ++i)
1093 int p = free_params_[i];
1094 ROS_ERROR(
"%u is %f", p, ik_seed_state[p]);
1095 vfree[i] = ik_seed_state[p];
1099 transformToChainFrame(ik_pose, frame);
1102 size_t numsol = solve(frame, vfree, solutions);
1105 std::vector<LimitObeyingSol> solutions_obey_limits;
1109 std::vector<double> solution_obey_limits;
1110 for (std::size_t
s = 0;
s < numsol; ++
s)
1112 std::vector<double> sol;
1113 getSolution(solutions, ik_seed_state,
s, sol);
1114 ROS_DEBUG_NAMED(name_,
"Sol %d: %e %e %e %e %e %e", static_cast<int>(
s), sol[0], sol[1], sol[2], sol[3],
1117 bool obeys_limits =
true;
1118 for (std::size_t i = 0; i < sol.size(); i++)
1121 if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
1125 obeys_limits =
false;
1127 <<
" has limit: " << joint_has_limits_vector_[i]
1128 <<
" being " << joint_min_vector_[i] <<
" to " 1129 << joint_max_vector_[i]);
1136 getSolution(solutions, ik_seed_state,
s, solution_obey_limits);
1137 double dist_from_seed = 0.0;
1138 for (std::size_t i = 0; i < ik_seed_state.size(); ++i)
1140 dist_from_seed += fabs(ik_seed_state[i] - solution_obey_limits[i]);
1143 solutions_obey_limits.push_back({ solution_obey_limits, dist_from_seed });
1153 if (!solutions_obey_limits.empty())
1155 std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
1156 solution = solutions_obey_limits[0].value;
1157 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
1161 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1165 bool IKFastKinematicsPlugin::getPositionIK(
const std::vector<geometry_msgs::Pose>& ik_poses,
1166 const std::vector<double>& ik_seed_state,
1167 std::vector<std::vector<double>>& solutions,
1180 if (ik_poses.empty())
1187 if (ik_poses.size() > 1)
1189 ROS_ERROR_NAMED(name_,
"ik_poses contains multiple entries, only one is allowed");
1194 if (ik_seed_state.size() < num_joints_)
1197 <<
" entries, this ikfast solver requires " << num_joints_);
1202 transformToChainFrame(ik_poses[0], frame);
1205 std::vector<IkSolutionList<IkReal>> solution_set;
1207 std::vector<double> vfree;
1209 std::vector<double> sampled_joint_vals;
1210 if (!redundant_joint_indices_.empty())
1213 sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]);
1217 joint_has_limits_vector_[redundant_joint_indices_.front()])
1219 double joint_min = joint_min_vector_[redundant_joint_indices_.front()];
1220 double joint_max = joint_max_vector_[redundant_joint_indices_.front()];
1222 double jv = sampled_joint_vals[0];
1238 for (
unsigned int i = 0; i < sampled_joint_vals.size(); i++)
1241 vfree.push_back(sampled_joint_vals[i]);
1242 numsol += solve(frame, vfree, ik_solutions);
1243 solution_set.push_back(ik_solutions);
1249 numsol = solve(frame, vfree, ik_solutions);
1250 solution_set.push_back(ik_solutions);
1254 bool solutions_found =
false;
1260 for (
unsigned int r = 0;
r < solution_set.size();
r++)
1262 ik_solutions = solution_set[
r];
1264 for (
int s = 0;
s < numsol; ++
s)
1266 std::vector<double> sol;
1267 getSolution(ik_solutions, ik_seed_state,
s, sol);
1269 bool obeys_limits =
true;
1270 for (
unsigned int i = 0; i < sol.size(); i++)
1273 if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
1277 obeys_limits =
false;
1279 << joint_has_limits_vector_[i] <<
" being " 1280 << joint_min_vector_[i] <<
" to " << joint_max_vector_[i]);
1287 solutions_found =
true;
1288 solutions.push_back(sol);
1293 if (solutions_found)
1309 std::vector<double>& sampled_joint_vals)
const 1311 int index = redundant_joint_indices_.front();
1312 double joint_dscrt = redundant_joint_discretization_.at(index);
1313 double joint_min = joint_min_vector_[index];
1314 double joint_max = joint_max_vector_[index];
1320 size_t steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1321 for (
size_t i = 0; i < steps; i++)
1323 sampled_joint_vals.push_back(joint_min + joint_dscrt * i);
1325 sampled_joint_vals.push_back(joint_max);
1330 int steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1331 steps = steps > 0 ? steps : 1;
1332 double diff = joint_max - joint_min;
1333 for (
int i = 0; i < steps; i++)
1335 sampled_joint_vals.push_back(((diff * std::rand()) / (static_cast<double>(RAND_MAX))) + joint_min);
1351 void IKFastKinematicsPlugin::transformToChainFrame(
const geometry_msgs::Pose& ik_pose,
KDL::Frame& ik_pose_chain)
const 1353 if (tip_transform_required_ || base_transform_required_)
1355 Eigen::Isometry3d ik_eigen_pose;
1357 if (tip_transform_required_)
1358 ik_eigen_pose = ik_eigen_pose * group_tip_to_chain_tip_;
1360 if (base_transform_required_)
1361 ik_eigen_pose = chain_base_to_group_base_ * ik_eigen_pose;
KinematicError kinematic_error
Eigen::Isometry3d chain_base_to_group_base_
SEARCH_MODE
Search modes for searchPositionIK(), see there.
end effector reaches desired 6D transformation
direction on end effector coordinate system points to desired 3D position
Eigen::Isometry3d group_tip_to_chain_tip_
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
std::vector< double > value
bool operator<(const LimitObeyingSol &a) const
void GetRPY(double &roll, double &pitch, double &yaw) const
ROSCONSOLE_DECL void initialize()
const JointModel * getParentJointModel() const
end effector reaches desired 3D rotation
UNSUPORTED_DISCRETIZATION_REQUESTED
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
std::vector< std::string > joint_names_
virtual const IkSolutionBase< T > & GetSolution(size_t index) const
returns the solution pointer
std::vector< std::string > link_names_
The discrete solutions are returned in this structure.
2D translation along XY plane
const double LIMIT_TOLERANCE
end effector origin reaches desired 3D translation
virtual void Clear()
clears all current solutions, note that any memory addresses returned from GetSolution will be invali...
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...
void transformEigenToKDL(const Eigen::Affine3d &e, KDL::Frame &k)
IKFAST_API bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
#define ROS_DEBUG_NAMED(name,...)
const LinkModel * getParentLinkModel() const
IKFAST_API int GetIkType()
#define ROS_WARN_STREAM_ONCE_NAMED(name, args)
the mask for the unique ids
void fromMsg(const A &, B &b)
std::size_t getVariableCount() const
PLUGINLIB_EXPORT_CLASS(fetch_arm::IKFastKinematicsPlugin, kinematics::KinematicsBase)
DiscretizationMethod discretization_method
const std::string & getName() const
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
const std::vector< std::string > & getLinkNames() const override
virtual void GetSolution(T *solution, const T *freevalues) const =0
gets a concrete solution
std::vector< double > joint_min_vector_
const VariableBounds & getVariableBounds(const std::string &variable) const
IKFAST_API int GetNumJoints()
ray on end effector coordinate system reaches desired global ray
IKFAST_API int * GetFreeParameters()
IKFAST_API void ComputeFk(const IkReal *j, IkReal *eetrans, IkReal *eerot)
Default implementation of IkSolutionListBase.
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR_NAMED(name,...)
const std::vector< std::string > & getJointNames() const override
std::vector< double > joint_max_vector_
IKFAST_API int GetNumFreeParameters()
MULTIPLE_TIPS_NOT_SUPPORTED
direction on end effector coordinate system reaches desired direction
bit is set if the data represents the time-derivate velocity of an IkParameterization ...
IkParameterizationType
The types of inverse kinematics parameterizations supported.
virtual size_t GetNumSolutions() const
returns the number of solutions stored
JointType getType() const
std::vector< bool > joint_has_limits_vector_
local point on end effector origin reaches desired 3D global point
#define ROS_WARN_STREAM_NAMED(name, args)
number of parameterizations (does not count IKP_None)
const std::string & getName() const