65 #define IKFAST_NO_MAIN // Don't include main() from IKFast 152 #include "_ROBOT_NAME___GROUP_NAME__ikfast_solver.cpp" 164 const std::string name_{
"ikfast" };
197 bool getPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
198 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
216 bool getPositionIK(
const std::vector<geometry_msgs::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
228 bool searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
229 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
241 bool searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
242 const std::vector<double>& consistency_limits, std::vector<double>& solution,
243 moveit_msgs::MoveItErrorCodes& error_code,
254 bool searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
255 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
256 moveit_msgs::MoveItErrorCodes& error_code,
269 bool searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
270 const std::vector<double>& consistency_limits, std::vector<double>& solution,
271 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
282 bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
283 std::vector<geometry_msgs::Pose>& poses)
const;
294 void setSearchDiscretization(
const std::map<int, double>& discretization);
299 bool setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices);
302 bool initialize(
const std::string& robot_description,
const std::string& group_name,
const std::string& base_name,
303 const std::string& tip_name,
double search_discretization);
309 int solve(
KDL::Frame& pose_frame,
const std::vector<double>& vfree, IkSolutionList<IkReal>& solutions)
const;
314 void getSolution(
const IkSolutionList<IkReal>& solutions,
int i, std::vector<double>& solution)
const;
319 void getSolution(
const IkSolutionList<IkReal>& solutions,
const std::vector<double>& ik_seed_state,
int i,
320 std::vector<double>& solution)
const;
322 double harmonize(
const std::vector<double>& ik_seed_state, std::vector<double>& solution)
const;
324 void getClosestSolution(
const IkSolutionList<IkReal>& solutions,
const std::vector<double>& ik_seed_state,
325 std::vector<double>& solution)
const;
326 void fillFreeParams(
int count,
int* array);
327 bool getCount(
int& count,
const int& max_count,
const int& min_count)
const;
340 const std::string& base_name,
const std::string& tip_name,
341 double search_discretization)
343 setValues(robot_description, group_name, base_name, tip_name, search_discretization);
348 lookupParam(
"robot", robot, std::string());
351 fillFreeParams(GetNumFreeParameters(), GetFreeParameters());
353 if (free_params_.size() > 1)
355 ROS_FATAL(
"Only one free joint parameter supported!");
358 else if (free_params_.size() == 1)
360 redundant_joint_indices_.clear();
361 redundant_joint_indices_.push_back(free_params_[0]);
362 KinematicsBase::setSearchDiscretization(DEFAULT_SEARCH_DISCRETIZATION);
368 std::string urdf_xml, full_urdf_xml;
369 lookupParam(
"urdf_xml", urdf_xml, robot_description);
373 if (!node_handle.
getParam(full_urdf_xml, xml_string))
375 ROS_FATAL_NAMED(name_,
"Could not load the xml from parameter server: %s", urdf_xml.c_str());
383 urdf::LinkConstSharedPtr link = robot_model.getLink(getTipFrame());
384 while (link->name != base_frame_ && joint_names_.size() <= num_joints_)
387 link_names_.push_back(link->name);
388 urdf::JointSharedPtr joint = link->parent_joint;
391 if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
395 joint_names_.push_back(joint->name);
398 if (joint->type != urdf::Joint::CONTINUOUS)
402 lower = joint->safety->soft_lower_limit;
403 upper = joint->safety->soft_upper_limit;
407 lower = joint->limits->lower;
408 upper = joint->limits->upper;
420 joint_has_limits_vector_.push_back(
true);
421 joint_min_vector_.push_back(lower);
422 joint_max_vector_.push_back(upper);
426 joint_has_limits_vector_.push_back(
false);
427 joint_min_vector_.push_back(-
M_PI);
428 joint_max_vector_.push_back(
M_PI);
434 ROS_WARN_NAMED(name_,
"no joint corresponding to %s", link->name.c_str());
436 link = link->getParent();
439 if (joint_names_.size() != num_joints_)
441 ROS_FATAL_STREAM_NAMED(name_,
"Joint numbers mismatch: URDF has " << joint_names_.size() <<
" and IKFast has " 446 std::reverse(link_names_.begin(), link_names_.end());
447 std::reverse(joint_names_.begin(), joint_names_.end());
448 std::reverse(joint_min_vector_.begin(), joint_min_vector_.end());
449 std::reverse(joint_max_vector_.begin(), joint_max_vector_.end());
450 std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end());
452 for (
size_t i = 0; i < num_joints_; ++i)
453 ROS_DEBUG_STREAM_NAMED(name_, joint_names_[i] <<
" " << joint_min_vector_[i] <<
" " << joint_max_vector_[i] <<
" " 454 << joint_has_limits_vector_[i]);
462 if (discretization.empty())
464 ROS_ERROR(
"The 'discretization' map is empty");
468 if (redundant_joint_indices_.empty())
474 if (discretization.begin()->first != redundant_joint_indices_[0])
476 std::string redundant_joint = joint_names_[free_params_[0]];
478 << discretization.begin()->first <<
", only joint '" << redundant_joint <<
"' with index " 479 << redundant_joint_indices_[0] <<
" is redundant.");
483 if (discretization.begin()->second <= 0.0)
489 redundant_joint_discretization_.clear();
490 redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second;
495 ROS_ERROR_STREAM(
"Changing the redundant joints isn't permitted by this group's solver ");
500 IkSolutionList<IkReal>& solutions)
const 506 trans[0] = pose_frame.
p[0];
507 trans[1] = pose_frame.
p[1];
508 trans[2] = pose_frame.
p[2];
522 vals[0] = mult(0, 0);
523 vals[1] = mult(0, 1);
524 vals[2] = mult(0, 2);
525 vals[3] = mult(1, 0);
526 vals[4] = mult(1, 1);
527 vals[5] = mult(1, 2);
528 vals[6] = mult(2, 0);
529 vals[7] = mult(2, 1);
530 vals[8] = mult(2, 2);
533 ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
534 return solutions.GetNumSolutions();
543 ComputeIk(trans, direction.
data, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
544 return solutions.GetNumSolutions();
552 ROS_ERROR_NAMED(name_,
"IK for this IkParameterizationType not implemented yet.");
558 ROS_ERROR_NAMED(name_,
"IK for this IkParameterizationType not implemented yet.");
565 ROS_ERROR_NAMED(name_,
"IK for this IkParameterizationType not implemented yet.");
569 double roll, pitch, yaw;
573 pose_frame.
M.
GetRPY(roll, pitch, yaw);
574 ComputeIk(trans, &yaw, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
575 return solutions.GetNumSolutions();
581 pose_frame.
M.
GetRPY(roll, pitch, yaw);
582 ComputeIk(trans, &roll, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
583 return solutions.GetNumSolutions();
589 pose_frame.
M.
GetRPY(roll, pitch, yaw);
590 ComputeIk(trans, &pitch, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
591 return solutions.GetNumSolutions();
595 "Was the solver generated with an incompatible version of Openrave?");
601 std::vector<double>& solution)
const 604 solution.resize(num_joints_);
607 const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
608 std::vector<IkReal> vsolfree(sol.GetFree().size());
609 sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : NULL);
620 const std::vector<double>& ik_seed_state,
int i,
621 std::vector<double>& solution)
const 624 solution.resize(num_joints_);
627 const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
628 std::vector<IkReal> vsolfree(sol.GetFree().size());
629 sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : NULL);
632 for (std::size_t i = 0; i < num_joints_; ++i)
634 if (joint_has_limits_vector_[i])
636 double signed_distance = solution[i] - ik_seed_state[i];
639 signed_distance -= 2 *
M_PI;
640 solution[i] -= 2 *
M_PI;
644 signed_distance += 2 *
M_PI;
645 solution[i] += 2 *
M_PI;
654 std::vector<double> ss = ik_seed_state;
655 for (
size_t i = 0; i < ik_seed_state.size(); ++i)
657 while (ss[i] > 2 *
M_PI)
661 while (ss[i] < 2 *
M_PI)
665 while (solution[i] > 2 *
M_PI)
667 solution[i] -= 2 *
M_PI;
669 while (solution[i] < 2 *
M_PI)
671 solution[i] += 2 *
M_PI;
673 dist_sqr += fabs(ik_seed_state[i] - solution[i]);
702 const std::vector<double>& ik_seed_state,
703 std::vector<double>& solution)
const 705 double mindist = DBL_MAX;
707 std::vector<double> sol;
710 for (
size_t i = 0; i < solutions.GetNumSolutions(); ++i)
712 getSolution(solutions, i, sol);
713 double dist = harmonize(ik_seed_state, sol);
716 if (minindex == -1 || dist < mindist)
724 getSolution(solutions, minindex, solution);
725 harmonize(ik_seed_state, solution);
731 free_params_.clear();
732 for (
int i = 0; i < count; ++i)
733 free_params_.push_back(array[i]);
740 if (-count >= min_count)
745 else if (count + 1 <= max_count)
757 if (1 - count <= max_count)
762 else if (count - 1 >= min_count)
773 const std::vector<double>& joint_angles,
774 std::vector<geometry_msgs::Pose>& poses)
const 782 ROS_ERROR_NAMED(name_,
"Can only compute FK for Transform6D IK type!");
787 if (link_names.size() == 0)
793 if (link_names.size() != 1 || link_names[0] != getTipFrame())
795 ROS_ERROR_NAMED(name_,
"Can compute FK for %s only", getTipFrame().c_str());
801 IkReal eerot[9], eetrans[3];
803 if (joint_angles.size() != num_joints_)
809 IkReal
angles[num_joints_];
810 for (
unsigned char i = 0; i < num_joints_; i++)
811 angles[i] = joint_angles[i];
814 ComputeFk(angles, eetrans, eerot);
816 for (
int i = 0; i < 3; ++i)
817 p_out.
p.
data[i] = eetrans[i];
819 for (
int i = 0; i < 9; ++i)
820 p_out.
M.
data[i] = eerot[i];
829 const std::vector<double>& ik_seed_state,
double timeout,
830 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
834 std::vector<double> consistency_limits;
836 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
841 const std::vector<double>& ik_seed_state,
double timeout,
842 const std::vector<double>& consistency_limits,
843 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
847 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
852 const std::vector<double>& ik_seed_state,
double timeout,
853 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
854 moveit_msgs::MoveItErrorCodes& error_code,
857 std::vector<double> consistency_limits;
858 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
863 const std::vector<double>& ik_seed_state,
double timeout,
864 const std::vector<double>& consistency_limits,
865 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
866 moveit_msgs::MoveItErrorCodes& error_code,
875 if (free_params_.size() == 0)
879 std::vector<geometry_msgs::Pose> ik_poses(1, ik_pose);
880 std::vector<std::vector<double>> solutions;
883 if (!getPositionIK(ik_poses, ik_seed_state, solutions, kinematic_result, options))
886 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
891 std::vector<LimitObeyingSol> solutions_obey_limits;
892 for (std::size_t i = 0; i < solutions.size(); ++i)
895 for (std::size_t j = 0; j < ik_seed_state.size(); ++j)
897 dist_from_seed += fabs(ik_seed_state[j] - solutions[i][j]);
900 solutions_obey_limits.push_back({ solutions[i], dist_from_seed });
902 std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
905 if (!solution_callback.empty())
907 for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i)
909 solution_callback(ik_pose, solutions_obey_limits[i].
value, error_code);
910 if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
912 solution = solutions_obey_limits[i].value;
923 solution = solutions_obey_limits[0].value;
924 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
934 error_code.val = error_code.NO_IK_SOLUTION;
938 if (ik_seed_state.size() != num_joints_)
941 << ik_seed_state.size());
942 error_code.val = error_code.NO_IK_SOLUTION;
946 if (!consistency_limits.empty() && consistency_limits.size() != num_joints_)
948 ROS_ERROR_STREAM_NAMED(name_,
"Consistency limits be empty or must have size " << num_joints_ <<
" instead of size " 949 << consistency_limits.size());
950 error_code.val = error_code.NO_IK_SOLUTION;
960 std::vector<double> vfree(free_params_.size());
965 double initial_guess = ik_seed_state[free_params_[0]];
966 vfree[0] = initial_guess;
970 int num_positive_increments;
971 int num_negative_increments;
973 if (!consistency_limits.empty())
977 double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess + consistency_limits[free_params_[0]]);
978 double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess - consistency_limits[free_params_[0]]);
980 num_positive_increments = (int)((max_limit - initial_guess) / search_discretization_);
981 num_negative_increments = (int)((initial_guess - min_limit) / search_discretization_);
985 num_positive_increments = (joint_max_vector_[free_params_[0]] - initial_guess) / search_discretization_;
986 num_negative_increments = (initial_guess - joint_min_vector_[free_params_[0]]) / search_discretization_;
992 ROS_DEBUG_STREAM_NAMED(name_,
"Free param is " << free_params_[0] <<
" initial guess is " << initial_guess
993 <<
", # positive increments: " << num_positive_increments
994 <<
", # negative increments: " << num_negative_increments);
995 if ((search_mode &
OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000)
998 double best_costs = -1.0;
999 std::vector<double> best_solution;
1000 int nattempts = 0, nvalid = 0;
1004 IkSolutionList<IkReal> solutions;
1005 int numsol = solve(frame, vfree, solutions);
1013 for (
int s = 0;
s < numsol; ++
s)
1016 std::vector<double> sol;
1017 getSolution(solutions, ik_seed_state,
s, sol);
1019 bool obeys_limits =
true;
1020 for (
unsigned int i = 0; i < sol.size(); i++)
1022 if (joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
1024 obeys_limits =
false;
1032 getSolution(solutions, ik_seed_state,
s, solution);
1035 if (!solution_callback.empty())
1037 solution_callback(ik_pose, solution, error_code);
1041 error_code.val = error_code.SUCCESS;
1044 if (error_code.val == error_code.SUCCESS)
1047 if (search_mode & OPTIMIZE_MAX_JOINT)
1051 for (
unsigned int i = 0; i < solution.size(); i++)
1053 double d = fabs(ik_seed_state[i] - solution[i]);
1057 if (costs < best_costs || best_costs == -1.0)
1060 best_solution = solution;
1071 if (!getCount(counter, num_positive_increments, -num_negative_increments))
1074 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1078 vfree[0] = initial_guess + search_discretization_ * counter;
1084 if ((search_mode & OPTIMIZE_MAX_JOINT) && best_costs != -1.0)
1086 solution = best_solution;
1087 error_code.val = error_code.SUCCESS;
1092 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1098 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
1109 if (ik_seed_state.size() < num_joints_)
1111 ROS_ERROR_STREAM(
"ik_seed_state only has " << ik_seed_state.size() <<
" entries, this ikfast solver requires " 1117 for (std::size_t i = 0; i < ik_seed_state.size(); i++)
1120 if (joint_has_limits_vector_[i] && ((ik_seed_state[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
1124 <<
" has limit: " << joint_has_limits_vector_[i] <<
" being " 1125 << joint_min_vector_[i] <<
" to " << joint_max_vector_[i]);
1130 std::vector<double> vfree(free_params_.size());
1131 for (std::size_t i = 0; i < free_params_.size(); ++i)
1133 int p = free_params_[i];
1134 ROS_ERROR(
"%u is %f", p, ik_seed_state[p]);
1135 vfree[i] = ik_seed_state[p];
1141 IkSolutionList<IkReal> solutions;
1142 int numsol = solve(frame, vfree, solutions);
1145 std::vector<LimitObeyingSol> solutions_obey_limits;
1149 std::vector<double> solution_obey_limits;
1150 for (std::size_t
s = 0;
s < numsol; ++
s)
1152 std::vector<double> sol;
1153 getSolution(solutions, ik_seed_state,
s, sol);
1154 ROS_DEBUG_NAMED(name_,
"Sol %d: %e %e %e %e %e %e", (
int)
s, sol[0], sol[1], sol[2], sol[3], sol[4],
1157 bool obeys_limits =
true;
1158 for (std::size_t i = 0; i < sol.size(); i++)
1161 if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
1165 obeys_limits =
false;
1167 << joint_has_limits_vector_[i] <<
" being " 1168 << joint_min_vector_[i] <<
" to " << joint_max_vector_[i]);
1175 getSolution(solutions, ik_seed_state, s, solution_obey_limits);
1177 for (std::size_t i = 0; i < ik_seed_state.size(); ++i)
1179 dist_from_seed += fabs(ik_seed_state[i] - solution_obey_limits[i]);
1182 solutions_obey_limits.push_back({ solution_obey_limits, dist_from_seed });
1192 if (!solutions_obey_limits.empty())
1194 std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
1195 solution = solutions_obey_limits[0].value;
1196 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
1200 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1205 const std::vector<double>& ik_seed_state,
1206 std::vector<std::vector<double>>& solutions,
1219 if (ik_poses.empty())
1226 if (ik_poses.size() > 1)
1228 ROS_ERROR(
"ik_poses contains multiple entries, only one is allowed");
1233 if (ik_seed_state.size() < num_joints_)
1235 ROS_ERROR_STREAM(
"ik_seed_state only has " << ik_seed_state.size() <<
" entries, this ikfast solver requires " 1244 std::vector<IkSolutionList<IkReal>> solution_set;
1245 IkSolutionList<IkReal> ik_solutions;
1246 std::vector<double> vfree;
1248 std::vector<double> sampled_joint_vals;
1249 if (!redundant_joint_indices_.empty())
1252 sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]);
1256 joint_has_limits_vector_[redundant_joint_indices_.front()])
1258 double joint_min = joint_min_vector_[redundant_joint_indices_.front()];
1259 double joint_max = joint_max_vector_[redundant_joint_indices_.front()];
1261 double jv = sampled_joint_vals[0];
1277 for (
unsigned int i = 0; i < sampled_joint_vals.size(); i++)
1280 vfree.push_back(sampled_joint_vals[i]);
1281 numsol += solve(frame, vfree, ik_solutions);
1282 solution_set.push_back(ik_solutions);
1288 numsol = solve(frame, vfree, ik_solutions);
1289 solution_set.push_back(ik_solutions);
1293 bool solutions_found =
false;
1299 for (
unsigned int r = 0;
r < solution_set.size();
r++)
1301 ik_solutions = solution_set[
r];
1302 numsol = ik_solutions.GetNumSolutions();
1303 for (
int s = 0;
s < numsol; ++
s)
1305 std::vector<double> sol;
1306 getSolution(ik_solutions, ik_seed_state,
s, sol);
1308 bool obeys_limits =
true;
1309 for (
unsigned int i = 0; i < sol.size(); i++)
1312 if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
1316 obeys_limits =
false;
1318 << joint_has_limits_vector_[i] <<
" being " 1319 << joint_min_vector_[i] <<
" to " << joint_max_vector_[i]);
1326 solutions_found =
true;
1327 solutions.push_back(sol);
1332 if (solutions_found)
1348 std::vector<double>& sampled_joint_vals)
const 1350 double joint_min = -
M_PI;
1351 double joint_max =
M_PI;
1352 int index = redundant_joint_indices_.front();
1353 double joint_dscrt = redundant_joint_discretization_.at(index);
1355 if (joint_has_limits_vector_[redundant_joint_indices_.front()])
1357 joint_min = joint_min_vector_[index];
1358 joint_max = joint_max_vector_[index];
1365 int steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1366 for (
unsigned int i = 0; i < steps; i++)
1368 sampled_joint_vals.push_back(joint_min + joint_dscrt * i);
1370 sampled_joint_vals.push_back(joint_max);
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++)
1380 sampled_joint_vals.push_back(((diff * std::rand()) / (static_cast<double>(RAND_MAX))) + joint_min);
1389 ROS_ERROR_STREAM(
"Discretization method " << method <<
" is not supported");
KinematicError kinematic_error
bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_name, double search_discretization)
const std::vector< std::string > & getLinkNames() const
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
URDF_EXPORT bool initString(const std::string &xmlstring)
#define ROS_WARN_NAMED(name,...)
bool getCount(int &count, const int &max_count, const int &min_count) const
ROSCONSOLE_DECL void initialize()
the mask for the unique ids
void getClosestSolution(const IkSolutionList< IkReal > &solutions, const std::vector< double > &ik_seed_state, std::vector< double > &solution) const
void setSearchDiscretization(const std::map< int, double > &discretization)
Sets the discretization value for the redundant joint.
UNSUPORTED_DISCRETIZATION_REQUESTED
ray on end effector coordinate system reaches desired global ray
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
IkParameterizationType
The types of inverse kinematics parameterizations supported.
std::vector< int > free_params_
bool sampleRedundantJoint(kinematics::DiscretizationMethod method, std::vector< double > &sampled_joint_vals) const
samples the designated redundant joint using the chosen discretization method
local point on end effector origin reaches desired 3D global point
std::vector< std::string > link_names_
#define ROS_INFO_STREAM_NAMED(name, args)
bool operator<(const LimitObeyingSol &a) const
2D translation along XY plane
PLUGINLIB_EXPORT_CLASS(ikfast_kinematics_plugin::IKFastKinematicsPlugin, kinematics::KinematicsBase)
bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
Given a desired pose of the end-effector, search for the joint angles required to reach it...
const double LIMIT_TOLERANCE
void fillFreeParams(int count, int *array)
number of parameterizations (does not count IKP_None)
#define ROS_DEBUG_NAMED(name,...)
std::vector< double > value
bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices)
Overrides the default method to prevent changing the redundant joints.
#define ROS_WARN_STREAM_ONCE_NAMED(name, args)
end effector reaches desired 6D transformation
end effector reaches desired 3D rotation
#define ROS_FATAL_STREAM_NAMED(name, args)
bool searchParam(const std::string &key, std::string &result) const
std::vector< bool > joint_has_limits_vector_
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
direction on end effector coordinate system points to desired 3D position
DiscretizationMethod discretization_method
double harmonize(const std::vector< double > &ik_seed_state, std::vector< double > &solution) const
def xml_string(rootXml, addHeader=True)
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
void GetRPY(double &roll, double &pitch, double &yaw) const
direction on end effector coordinate system reaches desired direction
const std::vector< std::string > & getJointNames() const
bit is set if the data represents the time-derivate velocity of an IkParameterization ...
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
bool getParam(const std::string &key, std::string &s) const
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR_NAMED(name,...)
MULTIPLE_TIPS_NOT_SUPPORTED
#define ROS_ERROR_STREAM(args)
bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
Given a desired pose of the end-effector, compute the joint angles to reach it.
int solve(KDL::Frame &pose_frame, const std::vector< double > &vfree, IkSolutionList< IkReal > &solutions) const
Calls the IK solver from IKFast.
end effector origin reaches desired 3D translation
SEARCH_MODE
Search modes for searchPositionIK(), see there.
std::vector< double > joint_min_vector_
std::vector< std::string > joint_names_
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
Given a set of joint angles and a set of links, compute their pose.
std::vector< double > joint_max_vector_
void getSolution(const IkSolutionList< IkReal > &solutions, int i, std::vector< double > &solution) const
Gets a specific solution from the set.
#define ROS_WARN_STREAM_NAMED(name, args)