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 #include <moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h>
00039 #include <class_loader/class_loader.h>
00040
00041
00042 #include <tf_conversions/tf_kdl.h>
00043 #include <kdl_parser/kdl_parser.hpp>
00044
00045
00046 #include <urdf_model/model.h>
00047 #include <srdfdom/model.h>
00048
00049 #include <moveit/rdf_loader/rdf_loader.h>
00050
00051
00052 CLASS_LOADER_REGISTER_CLASS(kdl_kinematics_plugin::KDLKinematicsPlugin, kinematics::KinematicsBase)
00053
00054 namespace kdl_kinematics_plugin
00055 {
00056
00057 KDLKinematicsPlugin::KDLKinematicsPlugin():active_(false) {}
00058
00059 void KDLKinematicsPlugin::getRandomConfiguration(KDL::JntArray &jnt_array,
00060 bool lock_redundancy) const
00061 {
00062 std::vector<double> jnt_array_vector(dimension_,0.0);
00063 robot_state::JointStateGroup* joint_state_group = kinematic_state_->getJointStateGroup(getGroupName());
00064 joint_state_group->setToRandomValues();
00065 joint_state_group->getVariableValues(jnt_array_vector);
00066 for(std::size_t i=0; i < dimension_; ++i)
00067 {
00068 if(lock_redundancy)
00069 if(isRedundantJoint(i))
00070 continue;
00071 jnt_array(i) = jnt_array_vector[i];
00072 }
00073 }
00074
00075 bool KDLKinematicsPlugin::isRedundantJoint(unsigned int index) const
00076 {
00077 for(std::size_t j=0; j < redundant_joint_indices_.size(); ++j)
00078 if(redundant_joint_indices_[j] == index)
00079 return true;
00080 return false;
00081 }
00082
00083 void KDLKinematicsPlugin::getRandomConfiguration(const KDL::JntArray &seed_state,
00084 const std::vector<double> &consistency_limits,
00085 KDL::JntArray &jnt_array,
00086 bool lock_redundancy) const
00087 {
00088 std::vector<double> values, near;
00089 for(std::size_t i=0; i < dimension_; ++i)
00090 {
00091 near.push_back(seed_state(i));
00092 }
00093 robot_state::JointStateGroup* joint_state_group = kinematic_state_->getJointStateGroup(getGroupName());
00094 joint_state_group->setToRandomValuesNearBy(near, consistency_limits);
00095 joint_state_group->getVariableValues(values);
00096 for(std::size_t i=0; i < dimension_; ++i)
00097 {
00098 if(lock_redundancy)
00099 for(std::size_t j=0; j < redundant_joint_indices_.size(); ++j)
00100 if(redundant_joint_indices_[j] == i)
00101 continue;
00102 jnt_array(i) = values[i];
00103 }
00104 }
00105
00106 bool KDLKinematicsPlugin::checkConsistency(const KDL::JntArray& seed_state,
00107 const std::vector<double> &consistency_limits,
00108 const KDL::JntArray& solution) const
00109 {
00110 std::vector<double> seed_state_vector(dimension_), solution_vector(dimension_);
00111 for(std::size_t i = 0; i < dimension_; ++i)
00112 {
00113 seed_state_vector[i] = seed_state(i);
00114 solution_vector[i] = solution(i);
00115 }
00116 robot_state::JointStateGroup* joint_state_group = kinematic_state_->getJointStateGroup(getGroupName());
00117 robot_state::JointStateGroup* joint_state_group_2 = kinematic_state_2_->getJointStateGroup(getGroupName());
00118 joint_state_group->setVariableValues(seed_state_vector);
00119 joint_state_group_2->setVariableValues(solution_vector);
00120
00121 const std::vector<robot_state::JointState*>& joint_state_vector = joint_state_group->getJointStateVector();
00122 const std::vector<robot_state::JointState*>& joint_state_vector_2 = joint_state_group_2->getJointStateVector();
00123
00124 for(std::size_t i = 0; i < joint_state_vector.size(); ++i)
00125 {
00126 if(joint_state_vector[i]->distance(joint_state_vector_2[i]) > consistency_limits[i])
00127 return false;
00128 }
00129
00130 return true;
00131 }
00132
00133 bool KDLKinematicsPlugin::initialize(const std::string &robot_description,
00134 const std::string& group_name,
00135 const std::string& base_frame,
00136 const std::string& tip_frame,
00137 double search_discretization)
00138 {
00139 setValues(robot_description, group_name, base_frame, tip_frame, search_discretization);
00140
00141 ros::NodeHandle private_handle("~");
00142 rdf_loader::RDFLoader rdf_loader(robot_description_);
00143 const boost::shared_ptr<srdf::Model> &srdf = rdf_loader.getSRDF();
00144 const boost::shared_ptr<urdf::ModelInterface>& urdf_model = rdf_loader.getURDF();
00145
00146 if (!urdf_model || !srdf)
00147 {
00148 ROS_ERROR_NAMED("kdl","URDF and SRDF must be loaded for KDL kinematics solver to work.");
00149 return false;
00150 }
00151
00152 kinematic_model_.reset(new robot_model::RobotModel(urdf_model, srdf));
00153
00154 if(!kinematic_model_->hasJointModelGroup(group_name))
00155 {
00156 ROS_ERROR_NAMED("kdl","Kinematic model does not contain group %s", group_name.c_str());
00157 return false;
00158 }
00159 robot_model::JointModelGroup* joint_model_group = kinematic_model_->getJointModelGroup(group_name);
00160 if(!joint_model_group->isChain())
00161 {
00162 ROS_ERROR_NAMED("kdl","Group '%s' is not a chain", group_name.c_str());
00163 return false;
00164 }
00165
00166 KDL::Tree kdl_tree;
00167
00168 if (!kdl_parser::treeFromUrdfModel(*urdf_model, kdl_tree))
00169 {
00170 ROS_ERROR_NAMED("kdl","Could not initialize tree object");
00171 return false;
00172 }
00173 if (!kdl_tree.getChain(base_frame_, tip_frame_, kdl_chain_))
00174 {
00175 ROS_ERROR_NAMED("kdl","Could not initialize chain object");
00176 return false;
00177 }
00178
00179 dimension_ = joint_model_group->getVariableCount();
00180 ik_chain_info_.joint_names = joint_model_group->getJointModelNames();
00181 ik_chain_info_.limits = joint_model_group->getVariableLimits();
00182 fk_chain_info_.joint_names = ik_chain_info_.joint_names;
00183 fk_chain_info_.limits = ik_chain_info_.limits;
00184
00185 if(!joint_model_group->hasLinkModel(tip_frame_))
00186 {
00187 ROS_ERROR_NAMED("kdl","Could not find tip name in joint group '%s'", group_name.c_str());
00188 return false;
00189 }
00190 ik_chain_info_.link_names.push_back(tip_frame_);
00191 fk_chain_info_.link_names = joint_model_group->getLinkModelNames();
00192
00193 joint_min_.resize(ik_chain_info_.limits.size());
00194 joint_max_.resize(ik_chain_info_.limits.size());
00195
00196 for(unsigned int i=0; i < ik_chain_info_.limits.size(); i++)
00197 {
00198 joint_min_(i) = ik_chain_info_.limits[i].min_position;
00199 joint_max_(i) = ik_chain_info_.limits[i].max_position;
00200 }
00201
00202
00203 int max_solver_iterations;
00204 double epsilon;
00205 bool position_ik;
00206
00207 private_handle.param("max_solver_iterations", max_solver_iterations, 500);
00208 private_handle.param("epsilon", epsilon, 1e-5);
00209 private_handle.param(group_name+"/position_only_ik", position_ik, false);
00210 ROS_DEBUG_NAMED("kdl","Looking in private handle: %s for param name: %s",
00211 private_handle.getNamespace().c_str(),
00212 (group_name+"/position_only_ik").c_str());
00213
00214 if(position_ik)
00215 ROS_INFO_NAMED("kdl","Using position only ik");
00216
00217 num_possible_redundant_joints_ = kdl_chain_.getNrOfJoints() - joint_model_group->getMimicJointModels().size() - (position_ik? 3:6);
00218
00219
00220 bool has_mimic_joints = joint_model_group->getMimicJointModels().size() > 0;
00221 std::vector<unsigned int> redundant_joints_map_index;
00222
00223 std::vector<kdl_kinematics_plugin::JointMimic> mimic_joints;
00224 unsigned int joint_counter = 0;
00225 for(std::size_t i=0; i < kdl_chain_.getNrOfSegments(); ++i)
00226 {
00227
00228 if(joint_model_group->isActiveDOF(kdl_chain_.segments[i].getJoint().getName()))
00229 {
00230 kdl_kinematics_plugin::JointMimic mimic_joint;
00231 mimic_joint.reset(joint_counter);
00232 mimic_joint.joint_name = kdl_chain_.segments[i].getJoint().getName();
00233 mimic_joint.active = true;
00234 mimic_joints.push_back(mimic_joint);
00235 ++joint_counter;
00236 continue;
00237 }
00238 if(joint_model_group->hasJointModel(kdl_chain_.segments[i].getJoint().getName()))
00239 {
00240 if(joint_model_group->getJointModel(kdl_chain_.segments[i].getJoint().getName())->getMimic())
00241 {
00242 kdl_kinematics_plugin::JointMimic mimic_joint;
00243 mimic_joint.reset(joint_counter);
00244 mimic_joint.joint_name = kdl_chain_.segments[i].getJoint().getName();
00245 mimic_joint.offset = joint_model_group->getJointModel(kdl_chain_.segments[i].getJoint().getName())->getMimicOffset();
00246 mimic_joint.multiplier = joint_model_group->getJointModel(kdl_chain_.segments[i].getJoint().getName())->getMimicFactor();
00247 mimic_joints.push_back(mimic_joint);
00248 continue;
00249 }
00250 }
00251 }
00252 for(std::size_t i=0; i < mimic_joints.size(); ++i)
00253 {
00254 if(!mimic_joints[i].active)
00255 {
00256 const robot_model::JointModel* joint_model = joint_model_group->getJointModel(mimic_joints[i].joint_name)->getMimic();
00257 for(std::size_t j=0; j < mimic_joints.size(); ++j)
00258 {
00259 if(mimic_joints[j].joint_name == joint_model->getName())
00260 {
00261 mimic_joints[i].map_index = mimic_joints[j].map_index;
00262 }
00263 }
00264 }
00265 }
00266 mimic_joints_ = mimic_joints;
00267
00268
00269 kinematic_state_.reset(new robot_state::RobotState((const robot_model::RobotModelConstPtr) kinematic_model_));
00270 kinematic_state_2_.reset(new robot_state::RobotState((const robot_model::RobotModelConstPtr) kinematic_model_));
00271
00272
00273 position_ik_ = position_ik;
00274 joint_model_group_ = joint_model_group;
00275 max_solver_iterations_ = max_solver_iterations;
00276 epsilon_ = epsilon;
00277
00278 active_ = true;
00279 ROS_DEBUG_NAMED("kdl","KDL solver initialized");
00280 return true;
00281 }
00282
00283 bool KDLKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int> &redundant_joints)
00284 {
00285 if(num_possible_redundant_joints_ < 0)
00286 {
00287 ROS_ERROR_NAMED("kdl","This group cannot have redundant joints");
00288 return false;
00289 }
00290 if(redundant_joints.size() > num_possible_redundant_joints_)
00291 {
00292 ROS_ERROR_NAMED("kdl","This group can only have %d redundant joints", num_possible_redundant_joints_);
00293 return false;
00294 }
00295
00296
00297
00298
00299
00300
00301
00302
00303
00304
00305
00306
00307
00308
00309 std::vector<unsigned int> redundant_joints_map_index;
00310 for(std::size_t i=0; i < dimension_; ++i)
00311 {
00312 bool is_redundant_joint = false;
00313 for(std::size_t j=0; j < redundant_joints.size(); ++j)
00314 {
00315 if(i == redundant_joints[j])
00316 {
00317 is_redundant_joint = true;
00318 break;
00319 }
00320 }
00321 if(!is_redundant_joint)
00322 {
00323 redundant_joints_map_index.push_back(i);
00324 }
00325 }
00326 for(std::size_t i=0; i < redundant_joints_map_index.size(); ++i)
00327 ROS_DEBUG_NAMED("kdl","Redundant joint map index: %d %d", (int) i, (int) redundant_joints_map_index[i]);
00328
00329 redundant_joints_map_index_ = redundant_joints_map_index_;
00330 redundant_joint_indices_ = redundant_joints;
00331 return true;
00332 }
00333
00334 int KDLKinematicsPlugin::getJointIndex(const std::string &name) const
00335 {
00336 for (unsigned int i=0; i < ik_chain_info_.joint_names.size(); i++) {
00337 if (ik_chain_info_.joint_names[i] == name)
00338 return i;
00339 }
00340 return -1;
00341 }
00342
00343 int KDLKinematicsPlugin::getKDLSegmentIndex(const std::string &name) const
00344 {
00345 int i=0;
00346 while (i < (int)kdl_chain_.getNrOfSegments()) {
00347 if (kdl_chain_.getSegment(i).getName() == name) {
00348 return i+1;
00349 }
00350 i++;
00351 }
00352 return -1;
00353 }
00354
00355 bool KDLKinematicsPlugin::timedOut(const ros::WallTime &start_time, double duration) const
00356 {
00357 return ((ros::WallTime::now()-start_time).toSec() >= duration);
00358 }
00359
00360 bool KDLKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose,
00361 const std::vector<double> &ik_seed_state,
00362 std::vector<double> &solution,
00363 moveit_msgs::MoveItErrorCodes &error_code,
00364 const kinematics::KinematicsQueryOptions &options) const
00365 {
00366 const IKCallbackFn solution_callback = 0;
00367 std::vector<double> consistency_limits;
00368
00369 return searchPositionIK(ik_pose,
00370 ik_seed_state,
00371 default_timeout_,
00372 solution,
00373 solution_callback,
00374 error_code,
00375 consistency_limits,
00376 options);
00377 }
00378
00379 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00380 const std::vector<double> &ik_seed_state,
00381 double timeout,
00382 std::vector<double> &solution,
00383 moveit_msgs::MoveItErrorCodes &error_code,
00384 const kinematics::KinematicsQueryOptions &options) const
00385 {
00386 const IKCallbackFn solution_callback = 0;
00387 std::vector<double> consistency_limits;
00388
00389 return searchPositionIK(ik_pose,
00390 ik_seed_state,
00391 timeout,
00392 solution,
00393 solution_callback,
00394 error_code,
00395 consistency_limits,
00396 options);
00397 }
00398
00399 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00400 const std::vector<double> &ik_seed_state,
00401 double timeout,
00402 const std::vector<double> &consistency_limits,
00403 std::vector<double> &solution,
00404 moveit_msgs::MoveItErrorCodes &error_code,
00405 const kinematics::KinematicsQueryOptions &options) const
00406 {
00407 const IKCallbackFn solution_callback = 0;
00408 return searchPositionIK(ik_pose,
00409 ik_seed_state,
00410 timeout,
00411 solution,
00412 solution_callback,
00413 error_code,
00414 consistency_limits,
00415 options);
00416 }
00417
00418 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00419 const std::vector<double> &ik_seed_state,
00420 double timeout,
00421 std::vector<double> &solution,
00422 const IKCallbackFn &solution_callback,
00423 moveit_msgs::MoveItErrorCodes &error_code,
00424 const kinematics::KinematicsQueryOptions &options) const
00425 {
00426 std::vector<double> consistency_limits;
00427 return searchPositionIK(ik_pose,
00428 ik_seed_state,
00429 timeout,
00430 solution,
00431 solution_callback,
00432 error_code,
00433 consistency_limits,
00434 options);
00435 }
00436
00437 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00438 const std::vector<double> &ik_seed_state,
00439 double timeout,
00440 const std::vector<double> &consistency_limits,
00441 std::vector<double> &solution,
00442 const IKCallbackFn &solution_callback,
00443 moveit_msgs::MoveItErrorCodes &error_code,
00444 const kinematics::KinematicsQueryOptions &options) const
00445 {
00446 return searchPositionIK(ik_pose,
00447 ik_seed_state,
00448 timeout,
00449 solution,
00450 solution_callback,
00451 error_code,
00452 consistency_limits,
00453 options);
00454 }
00455
00456 bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00457 const std::vector<double> &ik_seed_state,
00458 double timeout,
00459 std::vector<double> &solution,
00460 const IKCallbackFn &solution_callback,
00461 moveit_msgs::MoveItErrorCodes &error_code,
00462 const std::vector<double> &consistency_limits,
00463 const kinematics::KinematicsQueryOptions &options) const
00464 {
00465 ros::WallTime n1 = ros::WallTime::now();
00466 if(!active_)
00467 {
00468 ROS_ERROR_NAMED("kdl","kinematics not active");
00469 error_code.val = error_code.NO_IK_SOLUTION;
00470 return false;
00471 }
00472
00473 if(ik_seed_state.size() != dimension_)
00474 {
00475 ROS_ERROR_STREAM("Seed state must have size " << dimension_ << " instead of size " << ik_seed_state.size());
00476 error_code.val = error_code.NO_IK_SOLUTION;
00477 return false;
00478 }
00479
00480 if(!consistency_limits.empty() && consistency_limits.size() != dimension_)
00481 {
00482 ROS_ERROR_STREAM("Consistency limits be empty or must have size " << dimension_ << " instead of size " << consistency_limits.size());
00483 error_code.val = error_code.NO_IK_SOLUTION;
00484 return false;
00485 }
00486
00487 KDL::JntArray jnt_seed_state(dimension_);
00488 KDL::JntArray jnt_pos_in(dimension_);
00489 KDL::JntArray jnt_pos_out(dimension_);
00490
00491 KDL::ChainFkSolverPos_recursive fk_solver(kdl_chain_);
00492 KDL::ChainIkSolverVel_pinv_mimic ik_solver_vel(kdl_chain_, joint_model_group_->getMimicJointModels().size(), redundant_joint_indices_.size(), position_ik_);
00493 KDL::ChainIkSolverPos_NR_JL_Mimic ik_solver_pos(kdl_chain_, joint_min_, joint_max_, fk_solver, ik_solver_vel, max_solver_iterations_, epsilon_, position_ik_);
00494 ik_solver_vel.setMimicJoints(mimic_joints_);
00495 ik_solver_pos.setMimicJoints(mimic_joints_);
00496
00497 if ((redundant_joint_indices_.size() > 0) && !ik_solver_vel.setRedundantJointsMapIndex(redundant_joints_map_index_))
00498 {
00499 ROS_ERROR_NAMED("kdl","Could not set redundant joints");
00500 return false;
00501 }
00502
00503 if(options.lock_redundant_joints)
00504 {
00505 ik_solver_vel.lockRedundantJoints();
00506 }
00507
00508 solution.resize(dimension_);
00509
00510 KDL::Frame pose_desired;
00511 tf::poseMsgToKDL(ik_pose, pose_desired);
00512
00513 ROS_DEBUG_STREAM("searchPositionIK2: Position request pose is " <<
00514 ik_pose.position.x << " " <<
00515 ik_pose.position.y << " " <<
00516 ik_pose.position.z << " " <<
00517 ik_pose.orientation.x << " " <<
00518 ik_pose.orientation.y << " " <<
00519 ik_pose.orientation.z << " " <<
00520 ik_pose.orientation.w);
00521
00522 for(unsigned int i=0; i < dimension_; i++)
00523 jnt_seed_state(i) = ik_seed_state[i];
00524 jnt_pos_in = jnt_seed_state;
00525
00526 unsigned int counter(0);
00527 while(1)
00528 {
00529
00530 counter++;
00531 if(timedOut(n1,timeout))
00532 {
00533 ROS_DEBUG_NAMED("kdl","IK timed out");
00534 error_code.val = error_code.TIMED_OUT;
00535 ik_solver_vel.unlockRedundantJoints();
00536 return false;
00537 }
00538 int ik_valid = ik_solver_pos.CartToJnt(jnt_pos_in, pose_desired, jnt_pos_out);
00539 ROS_DEBUG_NAMED("kdl","IK valid: %d", ik_valid);
00540 if(!consistency_limits.empty())
00541 {
00542 getRandomConfiguration(jnt_seed_state, consistency_limits, jnt_pos_in, options.lock_redundant_joints);
00543 if( (ik_valid < 0 && !options.return_approximate_solution) || !checkConsistency(jnt_seed_state, consistency_limits, jnt_pos_out))
00544 {
00545 ROS_DEBUG_NAMED("kdl","Could not find IK solution: does not match consistency limits");
00546 continue;
00547 }
00548 }
00549 else
00550 {
00551 getRandomConfiguration(jnt_pos_in, options.lock_redundant_joints);
00552 ROS_DEBUG_NAMED("kdl","New random configuration");
00553 for(unsigned int j=0; j < dimension_; j++)
00554 ROS_DEBUG_NAMED("kdl","%d %f", j, jnt_pos_in(j));
00555
00556 if(ik_valid < 0 && !options.return_approximate_solution)
00557 {
00558 ROS_DEBUG_NAMED("kdl","Could not find IK solution");
00559 continue;
00560 }
00561 }
00562 ROS_DEBUG_NAMED("kdl","Found IK solution");
00563 for(unsigned int j=0; j < dimension_; j++)
00564 solution[j] = jnt_pos_out(j);
00565 if(!solution_callback.empty())
00566 solution_callback(ik_pose,solution,error_code);
00567 else
00568 error_code.val = error_code.SUCCESS;
00569
00570 if(error_code.val == error_code.SUCCESS)
00571 {
00572 ROS_DEBUG_STREAM("Solved after " << counter << " iterations");
00573 ik_solver_vel.unlockRedundantJoints();
00574 return true;
00575 }
00576 }
00577 ROS_DEBUG_NAMED("kdl","An IK that satisifes the constraints and is collision free could not be found");
00578 error_code.val = error_code.NO_IK_SOLUTION;
00579 ik_solver_vel.unlockRedundantJoints();
00580 return false;
00581 }
00582
00583 bool KDLKinematicsPlugin::getPositionFK(const std::vector<std::string> &link_names,
00584 const std::vector<double> &joint_angles,
00585 std::vector<geometry_msgs::Pose> &poses) const
00586 {
00587 ros::WallTime n1 = ros::WallTime::now();
00588 if(!active_)
00589 {
00590 ROS_ERROR_NAMED("kdl","kinematics not active");
00591 return false;
00592 }
00593 poses.resize(link_names.size());
00594 if(joint_angles.size() != dimension_)
00595 {
00596 ROS_ERROR_NAMED("kdl","Joint angles vector must have size: %d",dimension_);
00597 return false;
00598 }
00599
00600 KDL::Frame p_out;
00601 geometry_msgs::PoseStamped pose;
00602 tf::Stamped<tf::Pose> tf_pose;
00603
00604 KDL::JntArray jnt_pos_in(dimension_);
00605 for(unsigned int i=0; i < dimension_; i++)
00606 {
00607 jnt_pos_in(i) = joint_angles[i];
00608 }
00609
00610 KDL::ChainFkSolverPos_recursive fk_solver(kdl_chain_);
00611
00612 bool valid = true;
00613 for(unsigned int i=0; i < poses.size(); i++)
00614 {
00615 ROS_DEBUG_NAMED("kdl","End effector index: %d",getKDLSegmentIndex(link_names[i]));
00616 if(fk_solver.JntToCart(jnt_pos_in,p_out,getKDLSegmentIndex(link_names[i])) >=0)
00617 {
00618 tf::poseKDLToMsg(p_out,poses[i]);
00619 }
00620 else
00621 {
00622 ROS_ERROR_NAMED("kdl","Could not compute FK for %s",link_names[i].c_str());
00623 valid = false;
00624 }
00625 }
00626 return valid;
00627 }
00628
00629 const std::vector<std::string>& KDLKinematicsPlugin::getJointNames() const
00630 {
00631 return ik_chain_info_.joint_names;
00632 }
00633
00634 const std::vector<std::string>& KDLKinematicsPlugin::getLinkNames() const
00635 {
00636 return ik_chain_info_.link_names;
00637 }
00638
00639 }