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