00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075 #include <class_loader/class_loader.h>
00076
00077
00078 #include <tf_conversions/tf_kdl.h>
00079 #include <kdl_parser/kdl_parser.hpp>
00080
00081
00082 #include <urdf_model/model.h>
00083 #include <srdfdom/model.h>
00084
00085 #include <moveit/rdf_loader/rdf_loader.h>
00086
00087
00088 #include <ur_kinematics/ur_moveit_plugin.h>
00089 #include <ur_kinematics/ur_kin.h>
00090
00091
00092 CLASS_LOADER_REGISTER_CLASS(ur_kinematics::URKinematicsPlugin, kinematics::KinematicsBase)
00093
00094 namespace ur_kinematics
00095 {
00096
00097 URKinematicsPlugin::URKinematicsPlugin():active_(false) {}
00098
00099 void URKinematicsPlugin::getRandomConfiguration(KDL::JntArray &jnt_array, bool lock_redundancy) const
00100 {
00101 std::vector<double> jnt_array_vector(dimension_, 0.0);
00102 state_->setToRandomPositions(joint_model_group_);
00103 state_->copyJointGroupPositions(joint_model_group_, &jnt_array_vector[0]);
00104 for (std::size_t i = 0; i < dimension_; ++i)
00105 {
00106 if (lock_redundancy)
00107 if (isRedundantJoint(i))
00108 continue;
00109 jnt_array(i) = jnt_array_vector[i];
00110 }
00111 }
00112
00113 bool URKinematicsPlugin::isRedundantJoint(unsigned int index) const
00114 {
00115 for (std::size_t j=0; j < redundant_joint_indices_.size(); ++j)
00116 if (redundant_joint_indices_[j] == index)
00117 return true;
00118 return false;
00119 }
00120
00121 void URKinematicsPlugin::getRandomConfiguration(const KDL::JntArray &seed_state,
00122 const std::vector<double> &consistency_limits,
00123 KDL::JntArray &jnt_array,
00124 bool lock_redundancy) const
00125 {
00126 std::vector<double> values(dimension_, 0.0);
00127 std::vector<double> near(dimension_, 0.0);
00128 for (std::size_t i = 0 ; i < dimension_; ++i)
00129 near[i] = seed_state(i);
00130
00131
00132 std::vector<double> consistency_limits_mimic;
00133 for(std::size_t i = 0; i < dimension_; ++i)
00134 {
00135 if(!mimic_joints_[i].active)
00136 continue;
00137 consistency_limits_mimic.push_back(consistency_limits[i]);
00138 }
00139
00140 joint_model_group_->getVariableRandomPositionsNearBy(state_->getRandomNumberGenerator(), values, near, consistency_limits_mimic);
00141
00142 for (std::size_t i = 0; i < dimension_; ++i)
00143 {
00144 bool skip = false;
00145 if (lock_redundancy)
00146 for (std::size_t j = 0; j < redundant_joint_indices_.size(); ++j)
00147 if (redundant_joint_indices_[j] == i)
00148 {
00149 skip = true;
00150 break;
00151 }
00152 if (skip)
00153 continue;
00154 jnt_array(i) = values[i];
00155 }
00156 }
00157
00158 bool URKinematicsPlugin::checkConsistency(const KDL::JntArray& seed_state,
00159 const std::vector<double> &consistency_limits,
00160 const KDL::JntArray& solution) const
00161 {
00162 for (std::size_t i = 0; i < dimension_; ++i)
00163 if (fabs(seed_state(i) - solution(i)) > consistency_limits[i])
00164 return false;
00165 return true;
00166 }
00167
00168 bool URKinematicsPlugin::initialize(const std::string &robot_description,
00169 const std::string& group_name,
00170 const std::string& base_frame,
00171 const std::string& tip_frame,
00172 double search_discretization)
00173 {
00174 setValues(robot_description, group_name, base_frame, tip_frame, search_discretization);
00175
00176 ros::NodeHandle private_handle("~");
00177 rdf_loader::RDFLoader rdf_loader(robot_description_);
00178 const boost::shared_ptr<srdf::Model> &srdf = rdf_loader.getSRDF();
00179 const boost::shared_ptr<urdf::ModelInterface>& urdf_model = rdf_loader.getURDF();
00180
00181 if (!urdf_model || !srdf)
00182 {
00183 ROS_ERROR_NAMED("kdl","URDF and SRDF must be loaded for KDL kinematics solver to work.");
00184 return false;
00185 }
00186
00187 robot_model_.reset(new robot_model::RobotModel(urdf_model, srdf));
00188
00189 robot_model::JointModelGroup* joint_model_group = robot_model_->getJointModelGroup(group_name);
00190 if (!joint_model_group)
00191 return false;
00192
00193 if(!joint_model_group->isChain())
00194 {
00195 ROS_ERROR_NAMED("kdl","Group '%s' is not a chain", group_name.c_str());
00196 return false;
00197 }
00198 if(!joint_model_group->isSingleDOFJoints())
00199 {
00200 ROS_ERROR_NAMED("kdl","Group '%s' includes joints that have more than 1 DOF", group_name.c_str());
00201 return false;
00202 }
00203
00204 KDL::Tree kdl_tree;
00205
00206 if (!kdl_parser::treeFromUrdfModel(*urdf_model, kdl_tree))
00207 {
00208 ROS_ERROR_NAMED("kdl","Could not initialize tree object");
00209 return false;
00210 }
00211 if (!kdl_tree.getChain(base_frame_, getTipFrame(), kdl_chain_))
00212 {
00213 ROS_ERROR_NAMED("kdl","Could not initialize chain object");
00214 return false;
00215 }
00216
00217 dimension_ = joint_model_group->getActiveJointModels().size() + joint_model_group->getMimicJointModels().size();
00218 for (std::size_t i=0; i < joint_model_group->getJointModels().size(); ++i)
00219 {
00220 if(joint_model_group->getJointModels()[i]->getType() == moveit::core::JointModel::REVOLUTE || joint_model_group->getJointModels()[i]->getType() == moveit::core::JointModel::PRISMATIC)
00221 {
00222 ik_chain_info_.joint_names.push_back(joint_model_group->getJointModelNames()[i]);
00223 const std::vector<moveit_msgs::JointLimits> &jvec = joint_model_group->getJointModels()[i]->getVariableBoundsMsg();
00224 ik_chain_info_.limits.insert(ik_chain_info_.limits.end(), jvec.begin(), jvec.end());
00225 }
00226 }
00227
00228 fk_chain_info_.joint_names = ik_chain_info_.joint_names;
00229 fk_chain_info_.limits = ik_chain_info_.limits;
00230
00231 if(!joint_model_group->hasLinkModel(getTipFrame()))
00232 {
00233 ROS_ERROR_NAMED("kdl","Could not find tip name in joint group '%s'", group_name.c_str());
00234 return false;
00235 }
00236 ik_chain_info_.link_names.push_back(getTipFrame());
00237 fk_chain_info_.link_names = joint_model_group->getLinkModelNames();
00238
00239 joint_min_.resize(ik_chain_info_.limits.size());
00240 joint_max_.resize(ik_chain_info_.limits.size());
00241
00242 for(unsigned int i=0; i < ik_chain_info_.limits.size(); i++)
00243 {
00244 joint_min_(i) = ik_chain_info_.limits[i].min_position;
00245 joint_max_(i) = ik_chain_info_.limits[i].max_position;
00246 }
00247
00248
00249 int max_solver_iterations;
00250 double epsilon;
00251 bool position_ik;
00252
00253 private_handle.param("max_solver_iterations", max_solver_iterations, 500);
00254 private_handle.param("epsilon", epsilon, 1e-5);
00255 private_handle.param(group_name+"/position_only_ik", position_ik, false);
00256 ROS_DEBUG_NAMED("kdl","Looking in private handle: %s for param name: %s",
00257 private_handle.getNamespace().c_str(),
00258 (group_name+"/position_only_ik").c_str());
00259
00260 if(position_ik)
00261 ROS_INFO_NAMED("kdl","Using position only ik");
00262
00263 num_possible_redundant_joints_ = kdl_chain_.getNrOfJoints() - joint_model_group->getMimicJointModels().size() - (position_ik? 3:6);
00264
00265
00266 bool has_mimic_joints = joint_model_group->getMimicJointModels().size() > 0;
00267 std::vector<unsigned int> redundant_joints_map_index;
00268
00269 std::vector<kdl_kinematics_plugin::JointMimic> mimic_joints;
00270 unsigned int joint_counter = 0;
00271 for (std::size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
00272 {
00273 const robot_model::JointModel *jm = robot_model_->getJointModel(kdl_chain_.segments[i].getJoint().getName());
00274
00275
00276 if (jm->getMimic() == NULL && jm->getVariableCount() > 0)
00277 {
00278 kdl_kinematics_plugin::JointMimic mimic_joint;
00279 mimic_joint.reset(joint_counter);
00280 mimic_joint.joint_name = kdl_chain_.segments[i].getJoint().getName();
00281 mimic_joint.active = true;
00282 mimic_joints.push_back(mimic_joint);
00283 ++joint_counter;
00284 continue;
00285 }
00286 if (joint_model_group->hasJointModel(jm->getName()))
00287 {
00288 if (jm->getMimic() && joint_model_group->hasJointModel(jm->getMimic()->getName()))
00289 {
00290 kdl_kinematics_plugin::JointMimic mimic_joint;
00291 mimic_joint.reset(joint_counter);
00292 mimic_joint.joint_name = kdl_chain_.segments[i].getJoint().getName();
00293 mimic_joint.offset = jm->getMimicOffset();
00294 mimic_joint.multiplier = jm->getMimicFactor();
00295 mimic_joints.push_back(mimic_joint);
00296 continue;
00297 }
00298 }
00299 }
00300 for (std::size_t i = 0; i < mimic_joints.size(); ++i)
00301 {
00302 if(!mimic_joints[i].active)
00303 {
00304 const robot_model::JointModel* joint_model = joint_model_group->getJointModel(mimic_joints[i].joint_name)->getMimic();
00305 for(std::size_t j=0; j < mimic_joints.size(); ++j)
00306 {
00307 if(mimic_joints[j].joint_name == joint_model->getName())
00308 {
00309 mimic_joints[i].map_index = mimic_joints[j].map_index;
00310 }
00311 }
00312 }
00313 }
00314 mimic_joints_ = mimic_joints;
00315
00316
00317 state_.reset(new robot_state::RobotState(robot_model_));
00318 state_2_.reset(new robot_state::RobotState(robot_model_));
00319
00320
00321 position_ik_ = position_ik;
00322 joint_model_group_ = joint_model_group;
00323 max_solver_iterations_ = max_solver_iterations;
00324 epsilon_ = epsilon;
00325
00326 private_handle.param<std::string>("arm_prefix", arm_prefix_, "");
00327
00328 ur_joint_names_.push_back(arm_prefix_ + "shoulder_pan_joint");
00329 ur_joint_names_.push_back(arm_prefix_ + "shoulder_lift_joint");
00330 ur_joint_names_.push_back(arm_prefix_ + "elbow_joint");
00331 ur_joint_names_.push_back(arm_prefix_ + "wrist_1_joint");
00332 ur_joint_names_.push_back(arm_prefix_ + "wrist_2_joint");
00333 ur_joint_names_.push_back(arm_prefix_ + "wrist_3_joint");
00334
00335 ur_link_names_.push_back(arm_prefix_ + "base_link");
00336 ur_link_names_.push_back(arm_prefix_ + "ur_base_link");
00337 ur_link_names_.push_back(arm_prefix_ + "shoulder_link");
00338 ur_link_names_.push_back(arm_prefix_ + "upper_arm_link");
00339 ur_link_names_.push_back(arm_prefix_ + "forearm_link");
00340 ur_link_names_.push_back(arm_prefix_ + "wrist_1_link");
00341 ur_link_names_.push_back(arm_prefix_ + "wrist_2_link");
00342 ur_link_names_.push_back(arm_prefix_ + "wrist_3_link");
00343 ur_link_names_.push_back(arm_prefix_ + "ee_link");
00344
00345 ur_joint_inds_start_ = getJointIndex(ur_joint_names_[0]);
00346
00347
00348 int cur_ur_joint_ind, last_ur_joint_ind = ur_joint_inds_start_;
00349 for(int i=1; i<6; i++) {
00350 cur_ur_joint_ind = getJointIndex(ur_joint_names_[i]);
00351 if(cur_ur_joint_ind < 0) {
00352 ROS_ERROR_NAMED("kdl",
00353 "Kin chain provided in model doesn't contain standard UR joint '%s'.",
00354 ur_joint_names_[i].c_str());
00355 return false;
00356 }
00357 if(cur_ur_joint_ind != last_ur_joint_ind + 1) {
00358 ROS_ERROR_NAMED("kdl",
00359 "Kin chain provided in model doesn't have proper serial joint order: '%s'.",
00360 ur_joint_names_[i].c_str());
00361 return false;
00362 }
00363 last_ur_joint_ind = cur_ur_joint_ind;
00364 }
00365
00366
00367 kdl_tree.getChain(getBaseFrame(), ur_link_names_.front(), kdl_base_chain_);
00368 kdl_tree.getChain(ur_link_names_.back(), getTipFrame(), kdl_tip_chain_);
00369
00370
00371 ik_weights_.resize(6);
00372 if(private_handle.hasParam("ik_weights")) {
00373 private_handle.getParam("ik_weights", ik_weights_);
00374 } else {
00375 ik_weights_[0] = 1.0;
00376 ik_weights_[1] = 1.0;
00377 ik_weights_[2] = 0.1;
00378 ik_weights_[3] = 0.1;
00379 ik_weights_[4] = 0.3;
00380 ik_weights_[5] = 0.3;
00381 }
00382
00383 active_ = true;
00384 ROS_DEBUG_NAMED("kdl","KDL solver initialized");
00385 return true;
00386 }
00387
00388 bool URKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int> &redundant_joints)
00389 {
00390 if(num_possible_redundant_joints_ < 0)
00391 {
00392 ROS_ERROR_NAMED("kdl","This group cannot have redundant joints");
00393 return false;
00394 }
00395 if(redundant_joints.size() > num_possible_redundant_joints_)
00396 {
00397 ROS_ERROR_NAMED("kdl","This group can only have %d redundant joints", num_possible_redundant_joints_);
00398 return false;
00399 }
00400 std::vector<unsigned int> redundant_joints_map_index;
00401 unsigned int counter = 0;
00402 for(std::size_t i=0; i < dimension_; ++i)
00403 {
00404 bool is_redundant_joint = false;
00405 for(std::size_t j=0; j < redundant_joints.size(); ++j)
00406 {
00407 if(i == redundant_joints[j])
00408 {
00409 is_redundant_joint = true;
00410 counter++;
00411 break;
00412 }
00413 }
00414 if(!is_redundant_joint)
00415 {
00416
00417 if(mimic_joints_[i].active)
00418 {
00419 redundant_joints_map_index.push_back(counter);
00420 counter++;
00421 }
00422 }
00423 }
00424 for(std::size_t i=0; i < redundant_joints_map_index.size(); ++i)
00425 ROS_DEBUG_NAMED("kdl","Redundant joint map index: %d %d", (int) i, (int) redundant_joints_map_index[i]);
00426
00427 redundant_joints_map_index_ = redundant_joints_map_index;
00428 redundant_joint_indices_ = redundant_joints;
00429 return true;
00430 }
00431
00432 int URKinematicsPlugin::getJointIndex(const std::string &name) const
00433 {
00434 for (unsigned int i=0; i < ik_chain_info_.joint_names.size(); i++) {
00435 if (ik_chain_info_.joint_names[i] == name)
00436 return i;
00437 }
00438 return -1;
00439 }
00440
00441 int URKinematicsPlugin::getKDLSegmentIndex(const std::string &name) const
00442 {
00443 int i=0;
00444 while (i < (int)kdl_chain_.getNrOfSegments()) {
00445 if (kdl_chain_.getSegment(i).getName() == name) {
00446 return i+1;
00447 }
00448 i++;
00449 }
00450 return -1;
00451 }
00452
00453 bool URKinematicsPlugin::timedOut(const ros::WallTime &start_time, double duration) const
00454 {
00455 return ((ros::WallTime::now()-start_time).toSec() >= duration);
00456 }
00457
00458 bool URKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose,
00459 const std::vector<double> &ik_seed_state,
00460 std::vector<double> &solution,
00461 moveit_msgs::MoveItErrorCodes &error_code,
00462 const kinematics::KinematicsQueryOptions &options) const
00463 {
00464 const IKCallbackFn solution_callback = 0;
00465 std::vector<double> consistency_limits;
00466
00467 return searchPositionIK(ik_pose,
00468 ik_seed_state,
00469 default_timeout_,
00470 solution,
00471 solution_callback,
00472 error_code,
00473 consistency_limits,
00474 options);
00475 }
00476
00477 bool URKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00478 const std::vector<double> &ik_seed_state,
00479 double timeout,
00480 std::vector<double> &solution,
00481 moveit_msgs::MoveItErrorCodes &error_code,
00482 const kinematics::KinematicsQueryOptions &options) const
00483 {
00484 const IKCallbackFn solution_callback = 0;
00485 std::vector<double> consistency_limits;
00486
00487 return searchPositionIK(ik_pose,
00488 ik_seed_state,
00489 timeout,
00490 solution,
00491 solution_callback,
00492 error_code,
00493 consistency_limits,
00494 options);
00495 }
00496
00497 bool URKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00498 const std::vector<double> &ik_seed_state,
00499 double timeout,
00500 const std::vector<double> &consistency_limits,
00501 std::vector<double> &solution,
00502 moveit_msgs::MoveItErrorCodes &error_code,
00503 const kinematics::KinematicsQueryOptions &options) const
00504 {
00505 const IKCallbackFn solution_callback = 0;
00506 return searchPositionIK(ik_pose,
00507 ik_seed_state,
00508 timeout,
00509 solution,
00510 solution_callback,
00511 error_code,
00512 consistency_limits,
00513 options);
00514 }
00515
00516 bool URKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00517 const std::vector<double> &ik_seed_state,
00518 double timeout,
00519 std::vector<double> &solution,
00520 const IKCallbackFn &solution_callback,
00521 moveit_msgs::MoveItErrorCodes &error_code,
00522 const kinematics::KinematicsQueryOptions &options) const
00523 {
00524 std::vector<double> consistency_limits;
00525 return searchPositionIK(ik_pose,
00526 ik_seed_state,
00527 timeout,
00528 solution,
00529 solution_callback,
00530 error_code,
00531 consistency_limits,
00532 options);
00533 }
00534
00535 bool URKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00536 const std::vector<double> &ik_seed_state,
00537 double timeout,
00538 const std::vector<double> &consistency_limits,
00539 std::vector<double> &solution,
00540 const IKCallbackFn &solution_callback,
00541 moveit_msgs::MoveItErrorCodes &error_code,
00542 const kinematics::KinematicsQueryOptions &options) const
00543 {
00544 return searchPositionIK(ik_pose,
00545 ik_seed_state,
00546 timeout,
00547 solution,
00548 solution_callback,
00549 error_code,
00550 consistency_limits,
00551 options);
00552 }
00553
00554 typedef std::pair<int, double> idx_double;
00555 bool comparator(const idx_double& l, const idx_double& r)
00556 { return l.second < r.second; }
00557
00558 bool URKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00559 const std::vector<double> &ik_seed_state,
00560 double timeout,
00561 std::vector<double> &solution,
00562 const IKCallbackFn &solution_callback,
00563 moveit_msgs::MoveItErrorCodes &error_code,
00564 const std::vector<double> &consistency_limits,
00565 const kinematics::KinematicsQueryOptions &options) const
00566 {
00567 ros::WallTime n1 = ros::WallTime::now();
00568 if(!active_) {
00569 ROS_ERROR_NAMED("kdl","kinematics not active");
00570 error_code.val = error_code.NO_IK_SOLUTION;
00571 return false;
00572 }
00573
00574 if(ik_seed_state.size() != dimension_) {
00575 ROS_ERROR_STREAM_NAMED("kdl","Seed state must have size " << dimension_ << " instead of size " << ik_seed_state.size());
00576 error_code.val = error_code.NO_IK_SOLUTION;
00577 return false;
00578 }
00579
00580 if(!consistency_limits.empty() && consistency_limits.size() != dimension_) {
00581 ROS_ERROR_STREAM_NAMED("kdl","Consistency limits be empty or must have size " << dimension_ << " instead of size " << consistency_limits.size());
00582 error_code.val = error_code.NO_IK_SOLUTION;
00583 return false;
00584 }
00585
00586 KDL::JntArray jnt_seed_state(dimension_);
00587 for(int i=0; i<dimension_; i++)
00588 jnt_seed_state(i) = ik_seed_state[i];
00589
00590 solution.resize(dimension_);
00591
00592 KDL::ChainFkSolverPos_recursive fk_solver_base(kdl_base_chain_);
00593 KDL::ChainFkSolverPos_recursive fk_solver_tip(kdl_tip_chain_);
00594
00595 KDL::JntArray jnt_pos_test(jnt_seed_state);
00596 KDL::JntArray jnt_pos_base(ur_joint_inds_start_);
00597 KDL::JntArray jnt_pos_tip(dimension_ - 6 - ur_joint_inds_start_);
00598 KDL::Frame pose_base, pose_tip;
00599
00600 KDL::Frame kdl_ik_pose;
00601 KDL::Frame kdl_ik_pose_ur_chain;
00602 double homo_ik_pose[4][4];
00603 double q_ik_sols[8][6];
00604 uint16_t num_sols;
00605
00606 while(1) {
00607 if(timedOut(n1, timeout)) {
00608 ROS_DEBUG_NAMED("kdl","IK timed out");
00609 error_code.val = error_code.TIMED_OUT;
00610 return false;
00611 }
00612
00614
00615 for(uint32_t i=0; i<jnt_pos_base.rows(); i++)
00616 jnt_pos_base(i) = jnt_pos_test(i);
00617 for(uint32_t i=0; i<jnt_pos_tip.rows(); i++)
00618 jnt_pos_tip(i) = jnt_pos_test(i + ur_joint_inds_start_ + 6);
00619 for(uint32_t i=0; i<jnt_seed_state.rows(); i++)
00620 solution[i] = jnt_pos_test(i);
00621
00622 if(fk_solver_base.JntToCart(jnt_pos_base, pose_base) < 0) {
00623 ROS_ERROR_NAMED("kdl", "Could not compute FK for base chain");
00624 return false;
00625 }
00626
00627 if(fk_solver_tip.JntToCart(jnt_pos_tip, pose_tip) < 0) {
00628 ROS_ERROR_NAMED("kdl", "Could not compute FK for tip chain");
00629 return false;
00630 }
00632
00634
00635 tf::poseMsgToKDL(ik_pose, kdl_ik_pose);
00636 kdl_ik_pose_ur_chain = pose_base.Inverse() * kdl_ik_pose * pose_tip.Inverse();
00637
00638 kdl_ik_pose_ur_chain.Make4x4((double*) homo_ik_pose);
00639 #if KDL_OLD_BUG_FIX
00640
00641 for(int i=0; i<3; i++) homo_ik_pose[i][3] *= 1000;
00642 #endif
00643
00644
00645
00646 num_sols = inverse((double*) homo_ik_pose, (double*) q_ik_sols,
00647 jnt_pos_test(ur_joint_inds_start_+5));
00648
00649
00650 std::vector<idx_double> weighted_diffs;
00651 for(uint16_t i=0; i<num_sols; i++) {
00652 double cur_weighted_diff = 0;
00653 for(uint16_t j=0; j<6; j++) {
00654
00655 double abs_diff = std::fabs(ik_seed_state[ur_joint_inds_start_+j] - q_ik_sols[i][j]);
00656 if(!consistency_limits.empty() && abs_diff > consistency_limits[ur_joint_inds_start_+j]) {
00657 cur_weighted_diff = std::numeric_limits<double>::infinity();
00658 break;
00659 }
00660 cur_weighted_diff += ik_weights_[j] * abs_diff;
00661 }
00662 weighted_diffs.push_back(idx_double(i, cur_weighted_diff));
00663 }
00664
00665 std::sort(weighted_diffs.begin(), weighted_diffs.end(), comparator);
00666
00667 #if 0
00668 printf("start\n");
00669 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]);
00670 for(uint16_t i=0; i<weighted_diffs.size(); i++) {
00671 int cur_idx = weighted_diffs[i].first;
00672 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_sols[cur_idx][0], q_ik_sols[cur_idx][1], q_ik_sols[cur_idx][2], q_ik_sols[cur_idx][3], q_ik_sols[cur_idx][4], q_ik_sols[cur_idx][5]);
00673 }
00674 printf("end\n");
00675 #endif
00676
00677 for(uint16_t i=0; i<weighted_diffs.size(); i++) {
00678 if(weighted_diffs[i].second == std::numeric_limits<double>::infinity()) {
00679
00680 break;
00681 }
00682
00683
00684 int cur_idx = weighted_diffs[i].first;
00685 std::copy(q_ik_sols[cur_idx], q_ik_sols[cur_idx+1], solution.begin() + ur_joint_inds_start_);
00686
00687
00688 if(!solution_callback.empty())
00689 solution_callback(ik_pose, solution, error_code);
00690 else
00691 error_code.val = error_code.SUCCESS;
00692
00693 if(error_code.val == error_code.SUCCESS) {
00694 #if 0
00695 std::vector<std::string> fk_link_names;
00696 fk_link_names.push_back(ur_link_names_.back());
00697 std::vector<geometry_msgs::Pose> fk_poses;
00698 getPositionFK(fk_link_names, solution, fk_poses);
00699 KDL::Frame kdl_fk_pose;
00700 tf::poseMsgToKDL(fk_poses[0], kdl_fk_pose);
00701 printf("FK(solution) - pose \n");
00702 for(int i=0; i<4; i++) {
00703 for(int j=0; j<4; j++)
00704 printf("%1.6f ", kdl_fk_pose(i, j)-kdl_ik_pose(i, j));
00705 printf("\n");
00706 }
00707 #endif
00708 return true;
00709 }
00710 }
00711
00712
00713 if(options.lock_redundant_joints) {
00714 ROS_DEBUG_NAMED("kdl","Will not pertubate redundant joints to find solution");
00715 break;
00716 }
00717
00718 if(dimension_ == 6) {
00719 ROS_DEBUG_NAMED("kdl","No other joints to pertubate, cannot find solution");
00720 break;
00721 }
00722
00723
00724 if(!consistency_limits.empty()) {
00725 getRandomConfiguration(jnt_seed_state, consistency_limits, jnt_pos_test, false);
00726 } else {
00727 getRandomConfiguration(jnt_pos_test, false);
00728 }
00729 }
00730
00731 ROS_DEBUG_NAMED("kdl","An IK that satisifes the constraints and is collision free could not be found");
00732 error_code.val = error_code.NO_IK_SOLUTION;
00733 return false;
00734 }
00735
00736 bool URKinematicsPlugin::getPositionFK(const std::vector<std::string> &link_names,
00737 const std::vector<double> &joint_angles,
00738 std::vector<geometry_msgs::Pose> &poses) const
00739 {
00740 ros::WallTime n1 = ros::WallTime::now();
00741 if(!active_)
00742 {
00743 ROS_ERROR_NAMED("kdl","kinematics not active");
00744 return false;
00745 }
00746 poses.resize(link_names.size());
00747 if(joint_angles.size() != dimension_)
00748 {
00749 ROS_ERROR_NAMED("kdl","Joint angles vector must have size: %d",dimension_);
00750 return false;
00751 }
00752
00753 KDL::Frame p_out;
00754 geometry_msgs::PoseStamped pose;
00755 tf::Stamped<tf::Pose> tf_pose;
00756
00757 KDL::JntArray jnt_pos_in(dimension_);
00758 for(unsigned int i=0; i < dimension_; i++)
00759 {
00760 jnt_pos_in(i) = joint_angles[i];
00761 }
00762
00763 KDL::ChainFkSolverPos_recursive fk_solver(kdl_chain_);
00764
00765 bool valid = true;
00766 for(unsigned int i=0; i < poses.size(); i++)
00767 {
00768 ROS_DEBUG_NAMED("kdl","End effector index: %d",getKDLSegmentIndex(link_names[i]));
00769 if(fk_solver.JntToCart(jnt_pos_in,p_out,getKDLSegmentIndex(link_names[i])) >=0)
00770 {
00771 tf::poseKDLToMsg(p_out,poses[i]);
00772 }
00773 else
00774 {
00775 ROS_ERROR_NAMED("kdl","Could not compute FK for %s",link_names[i].c_str());
00776 valid = false;
00777 }
00778 }
00779 return valid;
00780 }
00781
00782 const std::vector<std::string>& URKinematicsPlugin::getJointNames() const
00783 {
00784 return ik_chain_info_.joint_names;
00785 }
00786
00787 const std::vector<std::string>& URKinematicsPlugin::getLinkNames() const
00788 {
00789 return ik_chain_info_.link_names;
00790 }
00791
00792 }