47 #include <Eigen/Geometry>
64 #define IKFAST_NO_MAIN // Don't include main() from IKFast
151 #include "_ROBOT_NAME___GROUP_NAME__ikfast_solver.cpp"
165 const std::string IKFAST_TIP_FRAME_ =
"_EEF_LINK_";
166 const std::string IKFAST_BASE_FRAME_ =
"_BASE_LINK_";
184 const std::string name_{
"ikfast" };
199 srand(time(
nullptr));
216 getPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
217 std::vector<double>& solution, 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;
332 size_t solve(KDL::Frame& pose_frame,
const std::vector<double>& vfree, IkSolutionList<IkReal>& solutions)
const;
337 void getSolution(
const IkSolutionList<IkReal>& solutions,
int i, std::vector<double>& solution)
const;
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;
377 robot_state = std::make_shared<RobotState>(robot_model_);
378 robot_state->setToDefaultValues();
381 auto* from_link = robot_model_->getLinkModel(from, &has_link);
382 auto* to_link = robot_model_->getLinkModel(to, &has_link);
383 if (!from_link || !to_link)
386 if (robot_model_->getRigidlyConnectedParentLinkModel(from_link) !=
387 robot_model_->getRigidlyConnectedParentLinkModel(to_link))
393 transform = robot_state->getGlobalLinkTransform(from_link).inverse() * robot_state->getGlobalLinkTransform(to_link);
394 differs_from_identity = !
transform.matrix().isIdentity();
399 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
400 double search_discretization)
402 if (tip_frames.size() != 1)
408 storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
409 if (!lookupParam(
"link_prefix", link_prefix_, std::string(
"")))
424 if (!robot_model.
hasLinkModel(link_prefix_ + IKFAST_TIP_FRAME_))
426 <<
"' does not exist. "
427 "Please check your link_prefix parameter.");
428 if (!robot_model.
hasLinkModel(link_prefix_ + IKFAST_BASE_FRAME_))
430 <<
"' does not exist. "
431 "Please check your link_prefix parameter.");
437 if (!computeRelativeTransform(tip_frames_[0], link_prefix_ + IKFAST_TIP_FRAME_, group_tip_to_chain_tip_,
438 tip_transform_required_) ||
439 !computeRelativeTransform(link_prefix_ + IKFAST_BASE_FRAME_, base_frame_, chain_base_to_group_base_,
440 base_transform_required_))
446 fillFreeParams(GetNumFreeParameters(), GetFreeParameters());
448 if (free_params_.size() > 1)
453 else if (free_params_.size() == 1)
455 redundant_joint_indices_.clear();
456 redundant_joint_indices_.push_back(free_params_[0]);
457 KinematicsBase::setSearchDiscretization(search_discretization);
470 while (link && link != base_link)
473 link_names_.push_back(link->
getName());
479 joint_names_.push_back(joint->
getName());
488 if (joint_names_.size() != num_joints_)
490 ROS_FATAL_NAMED(name_,
"Joint numbers of RobotModel (%zd) and IKFast solver (%zd) do not match",
491 joint_names_.size(), num_joints_);
495 std::reverse(link_names_.begin(), link_names_.end());
496 std::reverse(joint_names_.begin(), joint_names_.end());
497 std::reverse(joint_min_vector_.begin(), joint_min_vector_.end());
498 std::reverse(joint_max_vector_.begin(), joint_max_vector_.end());
499 std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end());
501 for (
size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
503 << joint_max_vector_[joint_id] <<
" "
504 << joint_has_limits_vector_[joint_id]);
510 void IKFastKinematicsPlugin::setSearchDiscretization(
const std::map<unsigned int, double>& discretization)
512 if (discretization.empty())
514 ROS_ERROR(
"The 'discretization' map is empty");
518 if (redundant_joint_indices_.empty())
524 if (discretization.begin()->first != redundant_joint_indices_[0])
526 std::string redundant_joint = joint_names_[free_params_[0]];
528 << discretization.begin()->first <<
", only joint '" << redundant_joint
529 <<
"' with index " << redundant_joint_indices_[0] <<
" is redundant.");
533 if (discretization.begin()->second <= 0.0)
539 redundant_joint_discretization_.clear();
540 redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second;
543 bool IKFastKinematicsPlugin::setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices)
549 size_t IKFastKinematicsPlugin::solve(KDL::Frame& pose_frame,
const std::vector<double>& vfree,
550 IkSolutionList<IkReal>& solutions)
const
556 trans[0] = pose_frame.p[0];
557 trans[1] = pose_frame.p[1];
558 trans[2] = pose_frame.p[2];
561 KDL::Vector direction;
574 vals[0] = mult(0, 0);
575 vals[1] = mult(0, 1);
576 vals[2] = mult(0, 2);
577 vals[3] = mult(1, 0);
578 vals[4] = mult(1, 1);
579 vals[5] = mult(1, 2);
580 vals[6] = mult(2, 0);
581 vals[7] = mult(2, 1);
582 vals[8] = mult(2, 2);
585 ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
586 return solutions.GetNumSolutions();
594 direction = pose_frame.M * KDL::Vector(_EEF_DIRECTION_);
597 direction.Normalize();
598 ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
599 return solutions.GetNumSolutions();
604 ROS_ERROR_NAMED(name_,
"IK for this IkParameterizationType not implemented yet.");
608 ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
609 return solutions.GetNumSolutions();
614 ROS_ERROR_NAMED(name_,
"IK for this IkParameterizationType not implemented yet.");
632 direction = pose_frame.M * KDL::Vector(_EEF_DIRECTION_);
635 direction.Normalize();
640 angle = std::acos(direction.x());
643 angle = std::acos(direction.y());
646 angle = std::acos(direction.z());
649 angle = std::atan2(direction.y(), direction.x());
652 angle = std::atan2(direction.z(), direction.y());
655 angle = std::atan2(direction.x(), direction.z());
662 ComputeIk(trans, &
angle, vfree.size() > 0 ? &vfree[0] :
nullptr, solutions);
663 return solutions.GetNumSolutions();
668 "Was the solver generated with an incompatible version of Openrave?");
673 void IKFastKinematicsPlugin::getSolution(
const IkSolutionList<IkReal>& solutions,
int i,
674 std::vector<double>& solution)
const
677 solution.resize(num_joints_);
680 const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
681 std::vector<IkReal> vsolfree(sol.GetFree().size());
682 sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] :
nullptr);
684 for (std::size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
686 if (joint_has_limits_vector_[joint_id])
688 solution[joint_id] = enforceLimits(solution[joint_id], joint_min_vector_[joint_id], joint_max_vector_[joint_id]);
693 void IKFastKinematicsPlugin::getSolution(
const IkSolutionList<IkReal>& solutions,
694 const std::vector<double>& ik_seed_state,
int i,
695 std::vector<double>& solution)
const
698 solution.resize(num_joints_);
701 const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
702 std::vector<IkReal> vsolfree(sol.GetFree().size());
703 sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] :
nullptr);
706 for (std::size_t i = 0; i < num_joints_; ++i)
708 if (joint_has_limits_vector_[i])
710 solution[i] = enforceLimits(solution[i], joint_min_vector_[i], joint_max_vector_[i]);
711 double signed_distance = solution[i] - ik_seed_state[i];
714 signed_distance -= 2 *
M_PI;
715 solution[i] -= 2 *
M_PI;
719 signed_distance += 2 *
M_PI;
720 solution[i] += 2 *
M_PI;
726 double IKFastKinematicsPlugin::enforceLimits(
double joint_value,
double min,
double max)
const
729 while (joint_value > max)
731 joint_value -= 2 *
M_PI;
735 while (joint_value < min)
737 joint_value += 2 *
M_PI;
742 void IKFastKinematicsPlugin::fillFreeParams(
int count,
int* array)
744 free_params_.clear();
745 for (
int i = 0; i < count; ++i)
746 free_params_.push_back(array[i]);
749 bool IKFastKinematicsPlugin::getCount(
int& count,
const int& max_count,
const int& min_count)
const
753 if (-count >= min_count)
758 else if (count + 1 <= max_count)
770 if (1 - count <= max_count)
775 else if (count - 1 >= min_count)
785 bool IKFastKinematicsPlugin::getPositionFK(
const std::vector<std::string>& link_names,
786 const std::vector<double>& joint_angles,
787 std::vector<geometry_msgs::Pose>& poses)
const
795 ROS_ERROR_NAMED(name_,
"Can only compute FK for Transform6D IK type!");
800 if (link_names.size() == 0)
806 if (link_names.size() != 1 || link_names[0] != getTipFrame())
808 ROS_ERROR_NAMED(name_,
"Can compute FK for %s only", getTipFrame().c_str());
814 IkReal eerot[9], eetrans[3];
816 if (joint_angles.size() != num_joints_)
822 IkReal
angles[num_joints_];
823 for (
unsigned char i = 0; i < num_joints_; i++)
824 angles[i] = joint_angles[i];
827 ComputeFk(
angles, eetrans, eerot);
829 for (
int i = 0; i < 3; ++i)
830 p_out.p.data[i] = eetrans[i];
832 for (
int i = 0; i < 9; ++i)
833 p_out.M.data[i] = eerot[i];
841 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose& ik_pose,
842 const std::vector<double>& ik_seed_state,
double timeout,
843 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
846 std::vector<double> consistency_limits;
847 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution,
IKCallbackFn(), error_code,
851 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose& ik_pose,
852 const std::vector<double>& ik_seed_state,
double timeout,
853 const std::vector<double>& consistency_limits,
854 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
857 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution,
IKCallbackFn(), error_code,
861 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose& ik_pose,
862 const std::vector<double>& ik_seed_state,
double timeout,
863 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
864 moveit_msgs::MoveItErrorCodes& error_code,
867 std::vector<double> consistency_limits;
868 return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
872 bool IKFastKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose& ik_pose,
873 const std::vector<double>& ik_seed_state,
double timeout,
874 const std::vector<double>& consistency_limits,
875 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
876 moveit_msgs::MoveItErrorCodes& error_code,
883 if (free_params_.size() == 0)
887 std::vector<geometry_msgs::Pose> ik_poses(1, ik_pose);
888 std::vector<std::vector<double>> solutions;
891 if (!getPositionIK(ik_poses, ik_seed_state, solutions, kinematic_result, options))
894 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
899 std::vector<LimitObeyingSol> solutions_obey_limits;
900 for (std::size_t i = 0; i < solutions.size(); ++i)
902 double dist_from_seed = 0.0;
903 for (std::size_t j = 0; j < ik_seed_state.size(); ++j)
905 dist_from_seed += fabs(ik_seed_state[j] - solutions[i][j]);
908 solutions_obey_limits.push_back({ solutions[i], dist_from_seed });
910 std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
913 if (!solution_callback.empty())
915 for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i)
917 solution_callback(ik_pose, solutions_obey_limits[i].value, error_code);
918 if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
920 solution = solutions_obey_limits[i].value;
931 solution = solutions_obey_limits[0].value;
932 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
942 error_code.val = error_code.NO_IK_SOLUTION;
946 if (ik_seed_state.size() != num_joints_)
949 "Seed state must have size " << num_joints_ <<
" instead of size " << ik_seed_state.size());
950 error_code.val = error_code.NO_IK_SOLUTION;
954 if (!consistency_limits.empty() && consistency_limits.size() != num_joints_)
956 ROS_ERROR_STREAM_NAMED(name_,
"Consistency limits be empty or must have size " << num_joints_ <<
" instead of size "
957 << consistency_limits.size());
958 error_code.val = error_code.NO_IK_SOLUTION;
966 transformToChainFrame(ik_pose, frame);
968 std::vector<double> vfree(free_params_.size());
972 double initial_guess = ik_seed_state[free_params_[0]];
973 vfree[0] = initial_guess;
977 int num_positive_increments;
978 int num_negative_increments;
979 double search_discretization = redundant_joint_discretization_.at(free_params_[0]);
981 if (!consistency_limits.empty())
985 double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess + consistency_limits[free_params_[0]]);
986 double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess - consistency_limits[free_params_[0]]);
988 num_positive_increments =
static_cast<int>((max_limit - initial_guess) / search_discretization);
989 num_negative_increments =
static_cast<int>((initial_guess - min_limit) / search_discretization);
993 num_positive_increments = (joint_max_vector_[free_params_[0]] - initial_guess) / search_discretization;
994 num_negative_increments = (initial_guess - joint_min_vector_[free_params_[0]]) / search_discretization;
1000 ROS_DEBUG_STREAM_NAMED(name_,
"Free param is " << free_params_[0] <<
" initial guess is " << initial_guess
1001 <<
", # positive increments: " << num_positive_increments
1002 <<
", # negative increments: " << num_negative_increments);
1003 if ((search_mode &
OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000)
1006 double best_costs = -1.0;
1007 std::vector<double> best_solution;
1008 int nattempts = 0, nvalid = 0;
1012 IkSolutionList<IkReal> solutions;
1013 size_t numsol = solve(frame, vfree, solutions);
1019 for (
size_t s = 0;
s < numsol; ++
s)
1022 std::vector<double> sol;
1023 getSolution(solutions, ik_seed_state,
s, sol);
1025 bool obeys_limits =
true;
1026 for (
size_t i = 0; i < sol.size(); i++)
1028 if (joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
1030 obeys_limits =
false;
1038 getSolution(solutions, ik_seed_state,
s, solution);
1041 if (!solution_callback.empty())
1043 solution_callback(ik_pose, solution, error_code);
1047 error_code.val = error_code.SUCCESS;
1050 if (error_code.val == error_code.SUCCESS)
1057 for (
unsigned int i = 0; i < solution.size(); i++)
1059 double d = fabs(ik_seed_state[i] - solution[i]);
1063 if (costs < best_costs || best_costs == -1.0)
1066 best_solution = solution;
1077 if (!getCount(counter, num_positive_increments, -num_negative_increments))
1080 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1084 vfree[0] = initial_guess + search_discretization * counter;
1092 solution = best_solution;
1093 error_code.val = error_code.SUCCESS;
1098 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1103 bool IKFastKinematicsPlugin::getPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
1104 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
1115 if (ik_seed_state.size() < num_joints_)
1118 <<
" entries, this ikfast solver requires " << num_joints_);
1123 for (std::size_t i = 0; i < ik_seed_state.size(); i++)
1126 if (joint_has_limits_vector_[i] && ((ik_seed_state[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
1129 ROS_DEBUG_STREAM_NAMED(name_,
"IK seed not in limits! " <<
static_cast<int>(i) <<
" value " << ik_seed_state[i]
1130 <<
" has limit: " << joint_has_limits_vector_[i]
1131 <<
" being " << joint_min_vector_[i] <<
" to "
1132 << joint_max_vector_[i]);
1137 std::vector<double> vfree(free_params_.size());
1138 for (std::size_t i = 0; i < free_params_.size(); ++i)
1140 int p = free_params_[i];
1141 ROS_ERROR(
"%u is %f", p, ik_seed_state[p]);
1142 vfree[i] = ik_seed_state[p];
1146 transformToChainFrame(ik_pose, frame);
1148 IkSolutionList<IkReal> solutions;
1149 size_t numsol = solve(frame, vfree, solutions);
1152 std::vector<LimitObeyingSol> solutions_obey_limits;
1156 std::vector<double> solution_obey_limits;
1157 for (std::size_t
s = 0;
s < numsol; ++
s)
1159 std::vector<double> sol;
1160 getSolution(solutions, ik_seed_state,
s, sol);
1161 ROS_DEBUG_NAMED(name_,
"Sol %d: %e %e %e %e %e %e",
static_cast<int>(
s), sol[0], sol[1], sol[2], sol[3],
1164 bool obeys_limits =
true;
1165 for (std::size_t i = 0; i < sol.size(); i++)
1168 if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
1172 obeys_limits =
false;
1174 <<
" has limit: " << joint_has_limits_vector_[i]
1175 <<
" being " << joint_min_vector_[i] <<
" to "
1176 << joint_max_vector_[i]);
1183 getSolution(solutions, ik_seed_state,
s, solution_obey_limits);
1184 double dist_from_seed = 0.0;
1185 for (std::size_t i = 0; i < ik_seed_state.size(); ++i)
1187 dist_from_seed += fabs(ik_seed_state[i] - solution_obey_limits[i]);
1190 solutions_obey_limits.push_back({ solution_obey_limits, dist_from_seed });
1200 if (!solutions_obey_limits.empty())
1202 std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end());
1203 solution = solutions_obey_limits[0].value;
1204 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
1208 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
1212 bool IKFastKinematicsPlugin::getPositionIK(
const std::vector<geometry_msgs::Pose>& ik_poses,
1213 const std::vector<double>& ik_seed_state,
1214 std::vector<std::vector<double>>& solutions,
1227 if (ik_poses.empty())
1234 if (ik_poses.size() > 1)
1236 ROS_ERROR_NAMED(name_,
"ik_poses contains multiple entries, only one is allowed");
1241 if (ik_seed_state.size() < num_joints_)
1244 <<
" entries, this ikfast solver requires " << num_joints_);
1249 transformToChainFrame(ik_poses[0], frame);
1252 std::vector<IkSolutionList<IkReal>> solution_set;
1253 IkSolutionList<IkReal> ik_solutions;
1254 std::vector<double> vfree;
1256 std::vector<double> sampled_joint_vals;
1257 if (!redundant_joint_indices_.empty())
1260 sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]);
1264 joint_has_limits_vector_[redundant_joint_indices_.front()])
1266 double joint_min = joint_min_vector_[redundant_joint_indices_.front()];
1267 double joint_max = joint_max_vector_[redundant_joint_indices_.front()];
1269 double jv = sampled_joint_vals[0];
1285 for (
unsigned int i = 0; i < sampled_joint_vals.size(); i++)
1288 vfree.push_back(sampled_joint_vals[i]);
1289 numsol += solve(frame, vfree, ik_solutions);
1290 solution_set.push_back(ik_solutions);
1296 numsol = solve(frame, vfree, ik_solutions);
1297 solution_set.push_back(ik_solutions);
1301 bool solutions_found =
false;
1307 for (
unsigned int r = 0;
r < solution_set.size();
r++)
1309 ik_solutions = solution_set[
r];
1310 numsol = ik_solutions.GetNumSolutions();
1311 for (
int s = 0;
s < numsol; ++
s)
1313 std::vector<double> sol;
1314 getSolution(ik_solutions, ik_seed_state,
s, sol);
1316 bool obeys_limits =
true;
1317 for (
unsigned int i = 0; i < sol.size(); i++)
1320 if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] -
LIMIT_TOLERANCE)) ||
1324 obeys_limits =
false;
1326 << joint_has_limits_vector_[i] <<
" being "
1327 << joint_min_vector_[i] <<
" to " << joint_max_vector_[i]);
1334 solutions_found =
true;
1335 solutions.push_back(sol);
1340 if (solutions_found)
1356 std::vector<double>& sampled_joint_vals)
const
1358 int index = redundant_joint_indices_.front();
1359 double joint_dscrt = redundant_joint_discretization_.at(
index);
1360 double joint_min = joint_min_vector_[
index];
1361 double joint_max = joint_max_vector_[
index];
1367 size_t steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1368 for (
size_t i = 0; i < steps; i++)
1370 sampled_joint_vals.push_back(joint_min + joint_dscrt * i);
1372 sampled_joint_vals.push_back(joint_max);
1377 int steps = std::ceil((joint_max - joint_min) / joint_dscrt);
1378 steps = steps > 0 ? steps : 1;
1379 double diff = joint_max - joint_min;
1380 for (
int i = 0; i < steps; i++)
1382 sampled_joint_vals.push_back(((diff * std::rand()) / (
static_cast<double>(RAND_MAX))) + joint_min);
1398 void IKFastKinematicsPlugin::transformToChainFrame(
const geometry_msgs::Pose& ik_pose, KDL::Frame& ik_pose_chain)
const
1400 if (tip_transform_required_ || base_transform_required_)
1402 Eigen::Isometry3d ik_eigen_pose;
1404 if (tip_transform_required_)
1405 ik_eigen_pose = ik_eigen_pose * group_tip_to_chain_tip_;
1407 if (base_transform_required_)
1408 ik_eigen_pose = chain_base_to_group_base_ * ik_eigen_pose;