79 #include <urdf_model/model.h>
97 void URKinematicsPlugin::getRandomConfiguration(KDL::JntArray &jnt_array,
bool lock_redundancy)
const
99 std::vector<double> jnt_array_vector(dimension_, 0.0);
100 state_->setToRandomPositions(joint_model_group_);
101 state_->copyJointGroupPositions(joint_model_group_, &jnt_array_vector[0]);
102 for (std::size_t i = 0; i < dimension_; ++i)
105 if (isRedundantJoint(i))
107 jnt_array(i) = jnt_array_vector[i];
111 bool URKinematicsPlugin::isRedundantJoint(
unsigned int index)
const
113 for (std::size_t j=0; j < redundant_joint_indices_.size(); ++j)
114 if (redundant_joint_indices_[j] == index)
119 void URKinematicsPlugin::getRandomConfiguration(
const KDL::JntArray &seed_state,
120 const std::vector<double> &consistency_limits,
121 KDL::JntArray &jnt_array,
122 bool lock_redundancy)
const
124 std::vector<double>
values(dimension_, 0.0);
125 std::vector<double> near(dimension_, 0.0);
126 for (std::size_t i = 0 ; i < dimension_; ++i)
127 near[i] = seed_state(i);
130 std::vector<double> consistency_limits_mimic;
131 for(std::size_t i = 0; i < dimension_; ++i)
133 if(!mimic_joints_[i].active)
135 consistency_limits_mimic.push_back(consistency_limits[i]);
138 joint_model_group_->getVariableRandomPositionsNearBy(state_->getRandomNumberGenerator(), values, near, consistency_limits_mimic);
140 for (std::size_t i = 0; i < dimension_; ++i)
144 for (std::size_t j = 0; j < redundant_joint_indices_.size(); ++j)
145 if (redundant_joint_indices_[j] == i)
156 bool URKinematicsPlugin::checkConsistency(
const KDL::JntArray& seed_state,
157 const std::vector<double> &consistency_limits,
158 const KDL::JntArray& solution)
const
160 for (std::size_t i = 0; i < dimension_; ++i)
161 if (fabs(seed_state(i) - solution(i)) > consistency_limits[i])
167 const std::string& group_name,
168 const std::string& base_frame,
169 const std::vector<std::string>& tip_frames,
170 double search_discretization)
172 storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
174 const robot_model::JointModelGroup* joint_model_group = robot_model_->getJointModelGroup(group_name);
175 if (!joint_model_group)
178 if(!joint_model_group->isChain())
180 ROS_ERROR_NAMED(
"kdl",
"Group '%s' is not a chain", group_name.c_str());
183 if(!joint_model_group->isSingleDOFJoints())
185 ROS_ERROR_NAMED(
"kdl",
"Group '%s' includes joints that have more than 1 DOF", group_name.c_str());
196 if (!kdl_tree.getChain(base_frame_, getTipFrame(), kdl_chain_))
202 dimension_ = joint_model_group->getActiveJointModels().size() + joint_model_group->getMimicJointModels().size();
203 for (std::size_t i=0; i < joint_model_group->getJointModels().size(); ++i)
207 ik_chain_info_.joint_names.push_back(joint_model_group->getJointModelNames()[i]);
208 const std::vector<moveit_msgs::JointLimits> &jvec = joint_model_group->getJointModels()[i]->getVariableBoundsMsg();
209 ik_chain_info_.limits.insert(ik_chain_info_.limits.end(), jvec.begin(), jvec.end());
213 fk_chain_info_.joint_names = ik_chain_info_.joint_names;
214 fk_chain_info_.limits = ik_chain_info_.limits;
216 if(!joint_model_group->hasLinkModel(getTipFrame()))
218 ROS_ERROR_NAMED(
"kdl",
"Could not find tip name in joint group '%s'", group_name.c_str());
221 ik_chain_info_.link_names.push_back(getTipFrame());
222 fk_chain_info_.link_names = joint_model_group->getLinkModelNames();
224 joint_min_.resize(ik_chain_info_.limits.size());
225 joint_max_.resize(ik_chain_info_.limits.size());
227 for(
unsigned int i=0; i < ik_chain_info_.limits.size(); i++)
229 joint_min_(i) = ik_chain_info_.limits[i].min_position;
230 joint_max_(i) = ik_chain_info_.limits[i].max_position;
234 int max_solver_iterations;
238 lookupParam(
"max_solver_iterations", max_solver_iterations, 500);
239 lookupParam(
"epsilon", epsilon, 1e-5);
240 lookupParam(group_name+
"/position_only_ik", position_ik,
false);
245 num_possible_redundant_joints_ = kdl_chain_.getNrOfJoints() - joint_model_group->getMimicJointModels().size() - (position_ik? 3:6);
248 bool has_mimic_joints = joint_model_group->getMimicJointModels().size() > 0;
249 std::vector<unsigned int> redundant_joints_map_index;
251 std::vector<kdl_kinematics_plugin::JointMimic> mimic_joints;
252 unsigned int joint_counter = 0;
253 for (std::size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
255 const robot_model::JointModel *jm = robot_model_->getJointModel(kdl_chain_.segments[i].getJoint().getName());
258 if (jm->getMimic() == NULL && jm->getVariableCount() > 0)
261 mimic_joint.
reset(joint_counter);
262 mimic_joint.
joint_name = kdl_chain_.segments[i].getJoint().getName();
263 mimic_joint.
active =
true;
264 mimic_joints.push_back(mimic_joint);
268 if (joint_model_group->hasJointModel(jm->getName()))
270 if (jm->getMimic() && joint_model_group->hasJointModel(jm->getMimic()->getName()))
273 mimic_joint.
reset(joint_counter);
274 mimic_joint.
joint_name = kdl_chain_.segments[i].getJoint().getName();
275 mimic_joint.
offset = jm->getMimicOffset();
276 mimic_joint.
multiplier = jm->getMimicFactor();
277 mimic_joints.push_back(mimic_joint);
282 for (std::size_t i = 0; i < mimic_joints.size(); ++i)
284 if(!mimic_joints[i].active)
286 const robot_model::JointModel* joint_model = joint_model_group->getJointModel(mimic_joints[i].joint_name)->getMimic();
287 for(std::size_t j=0; j < mimic_joints.size(); ++j)
289 if(mimic_joints[j].joint_name == joint_model->getName())
291 mimic_joints[i].map_index = mimic_joints[j].map_index;
296 mimic_joints_ = mimic_joints;
299 state_.reset(
new robot_state::RobotState(robot_model_));
300 state_2_.reset(
new robot_state::RobotState(robot_model_));
303 position_ik_ = position_ik;
304 joint_model_group_ = joint_model_group;
305 max_solver_iterations_ = max_solver_iterations;
308 lookupParam(
"arm_prefix", arm_prefix_, std::string(
""));
310 ur_joint_names_.push_back(arm_prefix_ +
"shoulder_pan_joint");
311 ur_joint_names_.push_back(arm_prefix_ +
"shoulder_lift_joint");
312 ur_joint_names_.push_back(arm_prefix_ +
"elbow_joint");
313 ur_joint_names_.push_back(arm_prefix_ +
"wrist_1_joint");
314 ur_joint_names_.push_back(arm_prefix_ +
"wrist_2_joint");
315 ur_joint_names_.push_back(arm_prefix_ +
"wrist_3_joint");
317 ur_link_names_.push_back(arm_prefix_ +
"base_link");
318 ur_link_names_.push_back(arm_prefix_ +
"ur_base_link");
319 ur_link_names_.push_back(arm_prefix_ +
"shoulder_link");
320 ur_link_names_.push_back(arm_prefix_ +
"upper_arm_link");
321 ur_link_names_.push_back(arm_prefix_ +
"forearm_link");
322 ur_link_names_.push_back(arm_prefix_ +
"wrist_1_link");
323 ur_link_names_.push_back(arm_prefix_ +
"wrist_2_link");
324 ur_link_names_.push_back(arm_prefix_ +
"wrist_3_link");
325 ur_link_names_.push_back(arm_prefix_ +
"ee_link");
327 ur_joint_inds_start_ = getJointIndex(ur_joint_names_[0]);
330 int cur_ur_joint_ind, last_ur_joint_ind = ur_joint_inds_start_;
331 for(
int i=1; i<6; i++) {
332 cur_ur_joint_ind = getJointIndex(ur_joint_names_[i]);
333 if(cur_ur_joint_ind < 0) {
335 "Kin chain provided in model doesn't contain standard UR joint '%s'.",
336 ur_joint_names_[i].c_str());
339 if(cur_ur_joint_ind != last_ur_joint_ind + 1) {
341 "Kin chain provided in model doesn't have proper serial joint order: '%s'.",
342 ur_joint_names_[i].c_str());
345 last_ur_joint_ind = cur_ur_joint_ind;
349 kdl_tree.getChain(getBaseFrame(), ur_link_names_.front(), kdl_base_chain_);
350 kdl_tree.getChain(ur_link_names_.back(), getTipFrame(), kdl_tip_chain_);
353 ik_weights_.resize(6);
354 if(!lookupParam(
"ik_weights", ik_weights_, ik_weights_)) {
355 ik_weights_[0] = 1.0;
356 ik_weights_[1] = 1.0;
357 ik_weights_[2] = 1.0;
358 ik_weights_[3] = 1.0;
359 ik_weights_[4] = 1.0;
360 ik_weights_[5] = 1.0;
368 bool URKinematicsPlugin::setRedundantJoints(
const std::vector<unsigned int> &redundant_joints)
370 if(num_possible_redundant_joints_ < 0)
375 if(redundant_joints.size() > num_possible_redundant_joints_)
377 ROS_ERROR_NAMED(
"kdl",
"This group can only have %d redundant joints", num_possible_redundant_joints_);
380 std::vector<unsigned int> redundant_joints_map_index;
381 unsigned int counter = 0;
382 for(std::size_t i=0; i < dimension_; ++i)
384 bool is_redundant_joint =
false;
385 for(std::size_t j=0; j < redundant_joints.size(); ++j)
387 if(i == redundant_joints[j])
389 is_redundant_joint =
true;
394 if(!is_redundant_joint)
397 if(mimic_joints_[i].active)
399 redundant_joints_map_index.push_back(counter);
404 for(std::size_t i=0; i < redundant_joints_map_index.size(); ++i)
405 ROS_DEBUG_NAMED(
"kdl",
"Redundant joint map index: %d %d", (
int) i, (
int) redundant_joints_map_index[i]);
407 redundant_joints_map_index_ = redundant_joints_map_index;
408 redundant_joint_indices_ = redundant_joints;
412 int URKinematicsPlugin::getJointIndex(
const std::string &name)
const
414 for (
unsigned int i=0; i < ik_chain_info_.joint_names.size(); i++) {
415 if (ik_chain_info_.joint_names[i] == name)
421 int URKinematicsPlugin::getKDLSegmentIndex(
const std::string &name)
const
424 while (i < (
int)kdl_chain_.getNrOfSegments()) {
425 if (kdl_chain_.getSegment(i).getName() == name) {
438 bool URKinematicsPlugin::getPositionIK(
const geometry_msgs::Pose &ik_pose,
439 const std::vector<double> &ik_seed_state,
440 std::vector<double> &solution,
441 moveit_msgs::MoveItErrorCodes &error_code,
444 const IKCallbackFn solution_callback = 0;
445 std::vector<double> consistency_limits;
447 return searchPositionIK(ik_pose,
457 bool URKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose &ik_pose,
458 const std::vector<double> &ik_seed_state,
460 std::vector<double> &solution,
461 moveit_msgs::MoveItErrorCodes &error_code,
464 const IKCallbackFn solution_callback = 0;
465 std::vector<double> consistency_limits;
467 return searchPositionIK(ik_pose,
477 bool URKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose &ik_pose,
478 const std::vector<double> &ik_seed_state,
480 const std::vector<double> &consistency_limits,
481 std::vector<double> &solution,
482 moveit_msgs::MoveItErrorCodes &error_code,
486 return searchPositionIK(ik_pose,
496 bool URKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose &ik_pose,
497 const std::vector<double> &ik_seed_state,
499 std::vector<double> &solution,
501 moveit_msgs::MoveItErrorCodes &error_code,
504 std::vector<double> consistency_limits;
505 return searchPositionIK(ik_pose,
515 bool URKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose &ik_pose,
516 const std::vector<double> &ik_seed_state,
518 const std::vector<double> &consistency_limits,
519 std::vector<double> &solution,
520 const IKCallbackFn &solution_callback,
521 moveit_msgs::MoveItErrorCodes &error_code,
524 return searchPositionIK(ik_pose,
536 {
return l.second <
r.second; }
538 bool URKinematicsPlugin::searchPositionIK(
const geometry_msgs::Pose &ik_pose,
539 const std::vector<double> &ik_seed_state,
541 std::vector<double> &solution,
543 moveit_msgs::MoveItErrorCodes &error_code,
544 const std::vector<double> &consistency_limits,
550 error_code.val = error_code.NO_IK_SOLUTION;
554 if(ik_seed_state.size() != dimension_) {
555 ROS_ERROR_STREAM_NAMED(
"kdl",
"Seed state must have size " << dimension_ <<
" instead of size " << ik_seed_state.size());
556 error_code.val = error_code.NO_IK_SOLUTION;
560 if(!consistency_limits.empty() && consistency_limits.size() != dimension_) {
561 ROS_ERROR_STREAM_NAMED(
"kdl",
"Consistency limits be empty or must have size " << dimension_ <<
" instead of size " << consistency_limits.size());
562 error_code.val = error_code.NO_IK_SOLUTION;
566 KDL::JntArray jnt_seed_state(dimension_);
567 for(
int i=0; i<dimension_; i++)
568 jnt_seed_state(i) = ik_seed_state[i];
570 solution.resize(dimension_);
572 KDL::ChainFkSolverPos_recursive fk_solver_base(kdl_base_chain_);
573 KDL::ChainFkSolverPos_recursive fk_solver_tip(kdl_tip_chain_);
575 KDL::JntArray jnt_pos_test(jnt_seed_state);
576 KDL::JntArray jnt_pos_base(ur_joint_inds_start_);
577 KDL::JntArray jnt_pos_tip(dimension_ - 6 - ur_joint_inds_start_);
578 KDL::Frame pose_base, pose_tip;
580 KDL::Frame kdl_ik_pose;
581 KDL::Frame kdl_ik_pose_ur_chain;
582 double homo_ik_pose[4][4];
583 double q_ik_sols[8][6];
587 if(timedOut(n1, timeout)) {
589 error_code.val = error_code.TIMED_OUT;
595 for(uint32_t i=0; i<jnt_pos_base.rows(); i++)
596 jnt_pos_base(i) = jnt_pos_test(i);
597 for(uint32_t i=0; i<jnt_pos_tip.rows(); i++)
598 jnt_pos_tip(i) = jnt_pos_test(i + ur_joint_inds_start_ + 6);
599 for(uint32_t i=0; i<jnt_seed_state.rows(); i++)
600 solution[i] = jnt_pos_test(i);
602 if(fk_solver_base.JntToCart(jnt_pos_base, pose_base) < 0) {
607 if(fk_solver_tip.JntToCart(jnt_pos_tip, pose_tip) < 0) {
616 kdl_ik_pose_ur_chain = pose_base.Inverse() * kdl_ik_pose * pose_tip.Inverse();
618 kdl_ik_pose_ur_chain.Make4x4((
double*) homo_ik_pose);
621 for(
int i=0; i<3; i++) homo_ik_pose[i][3] *= 1000;
626 num_sols =
inverse((
double*) homo_ik_pose, (
double*) q_ik_sols,
627 jnt_pos_test(ur_joint_inds_start_+5));
630 uint16_t num_valid_sols;
631 std::vector< std::vector<double> > q_ik_valid_sols;
632 for(uint16_t i=0; i<num_sols; i++)
635 std::vector< double > valid_solution;
636 valid_solution.assign(6,0.0);
638 for(uint16_t j=0; j<6; j++)
640 if((q_ik_sols[i][j] <= ik_chain_info_.limits[j].max_position) && (q_ik_sols[i][j] >= ik_chain_info_.limits[j].min_position))
642 valid_solution[j] = q_ik_sols[i][j];
646 else if ((q_ik_sols[i][j] > ik_chain_info_.limits[j].max_position) && (q_ik_sols[i][j]-2*M_PI > ik_chain_info_.limits[j].min_position))
648 valid_solution[j] = q_ik_sols[i][j]-2*
M_PI;
652 else if ((q_ik_sols[i][j] < ik_chain_info_.limits[j].min_position) && (q_ik_sols[i][j]+2*M_PI < ik_chain_info_.limits[j].max_position))
654 valid_solution[j] = q_ik_sols[i][j]+2*
M_PI;
667 q_ik_valid_sols.push_back(valid_solution);
673 std::vector<idx_double> weighted_diffs;
674 for(uint16_t i=0; i<q_ik_valid_sols.size(); i++) {
675 double cur_weighted_diff = 0;
676 for(uint16_t j=0; j<6; j++) {
678 double abs_diff = std::fabs(ik_seed_state[ur_joint_inds_start_+j] - q_ik_valid_sols[i][j]);
679 if(!consistency_limits.empty() && abs_diff > consistency_limits[ur_joint_inds_start_+j]) {
680 cur_weighted_diff = std::numeric_limits<double>::infinity();
683 cur_weighted_diff += ik_weights_[j] * abs_diff;
685 weighted_diffs.push_back(
idx_double(i, cur_weighted_diff));
688 std::sort(weighted_diffs.begin(), weighted_diffs.end(),
comparator);
692 printf(
" q %1.2f, %1.2f, %1.2f, %1.2f, %1.2f, %1.2f\n", ik_seed_state[1], ik_seed_state[2], ik_seed_state[3], ik_seed_state[4], ik_seed_state[5], ik_seed_state[6]);
693 for(uint16_t i=0; i<weighted_diffs.size(); i++) {
694 int cur_idx = weighted_diffs[i].first;
695 printf(
"diff %f, i %d, q %1.2f, %1.2f, %1.2f, %1.2f, %1.2f, %1.2f\n", weighted_diffs[i].second, cur_idx, q_ik_valid_sols[cur_idx][0], q_ik_valid_sols[cur_idx][1], q_ik_valid_sols[cur_idx][2], q_ik_valid_sols[cur_idx][3], q_ik_valid_sols[cur_idx][4], q_ik_valid_sols[cur_idx][5]);
700 for(uint16_t i=0; i<weighted_diffs.size(); i++) {
701 if(weighted_diffs[i].second == std::numeric_limits<double>::infinity()) {
707 int cur_idx = weighted_diffs[i].first;
708 solution = q_ik_valid_sols[cur_idx];
711 if(!solution_callback.empty())
712 solution_callback(ik_pose, solution, error_code);
714 error_code.val = error_code.SUCCESS;
716 if(error_code.val == error_code.SUCCESS) {
718 std::vector<std::string> fk_link_names;
719 fk_link_names.push_back(ur_link_names_.back());
720 std::vector<geometry_msgs::Pose> fk_poses;
721 getPositionFK(fk_link_names, solution, fk_poses);
722 KDL::Frame kdl_fk_pose;
724 printf(
"FK(solution) - pose \n");
725 for(
int i=0; i<4; i++) {
726 for(
int j=0; j<4; j++)
727 printf(
"%1.6f ", kdl_fk_pose(i, j)-kdl_ik_pose(i, j));
737 ROS_DEBUG_NAMED(
"kdl",
"Will not pertubate redundant joints to find solution");
741 if(dimension_ == 6) {
742 ROS_DEBUG_NAMED(
"kdl",
"No other joints to pertubate, cannot find solution");
747 if(!consistency_limits.empty()) {
748 getRandomConfiguration(jnt_seed_state, consistency_limits, jnt_pos_test,
false);
750 getRandomConfiguration(jnt_pos_test,
false);
754 ROS_DEBUG_NAMED(
"kdl",
"An IK that satisifes the constraints and is collision free could not be found");
755 error_code.val = error_code.NO_IK_SOLUTION;
759 bool URKinematicsPlugin::getPositionFK(
const std::vector<std::string> &link_names,
760 const std::vector<double> &joint_angles,
761 std::vector<geometry_msgs::Pose> &poses)
const
769 poses.resize(link_names.size());
770 if(joint_angles.size() != dimension_)
772 ROS_ERROR_NAMED(
"kdl",
"Joint angles vector must have size: %d",dimension_);
777 geometry_msgs::PoseStamped pose;
780 KDL::JntArray jnt_pos_in(dimension_);
781 for(
unsigned int i=0; i < dimension_; i++)
783 jnt_pos_in(i) = joint_angles[i];
786 KDL::ChainFkSolverPos_recursive fk_solver(kdl_chain_);
789 for(
unsigned int i=0; i < poses.size(); i++)
791 ROS_DEBUG_NAMED(
"kdl",
"End effector index: %d",getKDLSegmentIndex(link_names[i]));
792 if(fk_solver.JntToCart(jnt_pos_in,p_out,getKDLSegmentIndex(link_names[i])) >=0)
798 ROS_ERROR_NAMED(
"kdl",
"Could not compute FK for %s",link_names[i].c_str());
805 const std::vector<std::string>& URKinematicsPlugin::getJointNames()
const
807 return ik_chain_info_.joint_names;
810 const std::vector<std::string>& URKinematicsPlugin::getLinkNames()
const
812 return ik_chain_info_.link_names;