kdl_kinematics_plugin.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Sachin Chitta, David Lu!!, Ugo Cupcic */
00036 
00037 #include <moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h>
00038 #include <class_loader/class_loader.h>
00039 
00040 //#include <tf/transform_datatypes.h>
00041 #include <tf_conversions/tf_kdl.h>
00042 #include <kdl_parser/kdl_parser.hpp>
00043 
00044 // URDF, SRDF
00045 #include <urdf_model/model.h>
00046 #include <srdfdom/model.h>
00047 
00048 #include <moveit/rdf_loader/rdf_loader.h>
00049 
00050 // register KDLKinematics as a KinematicsBase implementation
00051 CLASS_LOADER_REGISTER_CLASS(kdl_kinematics_plugin::KDLKinematicsPlugin, kinematics::KinematicsBase)
00052 
00053 namespace kdl_kinematics_plugin
00054 {
00055 KDLKinematicsPlugin::KDLKinematicsPlugin() : active_(false)
00056 {
00057 }
00058 
00059 void KDLKinematicsPlugin::getRandomConfiguration(KDL::JntArray& jnt_array, bool lock_redundancy) const
00060 {
00061   std::vector<double> jnt_array_vector(dimension_, 0.0);
00062   state_->setToRandomPositions(joint_model_group_);
00063   state_->copyJointGroupPositions(joint_model_group_, &jnt_array_vector[0]);
00064   for (std::size_t i = 0; i < dimension_; ++i)
00065   {
00066     if (lock_redundancy)
00067       if (isRedundantJoint(i))
00068         continue;
00069     jnt_array(i) = jnt_array_vector[i];
00070   }
00071 }
00072 
00073 bool KDLKinematicsPlugin::isRedundantJoint(unsigned int index) const
00074 {
00075   for (std::size_t j = 0; j < redundant_joint_indices_.size(); ++j)
00076     if (redundant_joint_indices_[j] == index)
00077       return true;
00078   return false;
00079 }
00080 
00081 void KDLKinematicsPlugin::getRandomConfiguration(const KDL::JntArray& seed_state,
00082                                                  const std::vector<double>& consistency_limits,
00083                                                  KDL::JntArray& jnt_array, bool lock_redundancy) const
00084 {
00085   std::vector<double> values(dimension_, 0.0);
00086   std::vector<double> near(dimension_, 0.0);
00087   for (std::size_t i = 0; i < dimension_; ++i)
00088     near[i] = seed_state(i);
00089 
00090   // Need to resize the consistency limits to remove mimic joints
00091   std::vector<double> consistency_limits_mimic;
00092   for (std::size_t i = 0; i < dimension_; ++i)
00093   {
00094     if (!mimic_joints_[i].active)
00095       continue;
00096     consistency_limits_mimic.push_back(consistency_limits[i]);
00097   }
00098 
00099   joint_model_group_->getVariableRandomPositionsNearBy(state_->getRandomNumberGenerator(), values, near,
00100                                                        consistency_limits_mimic);
00101 
00102   for (std::size_t i = 0; i < dimension_; ++i)
00103   {
00104     bool skip = false;
00105     if (lock_redundancy)
00106       for (std::size_t j = 0; j < redundant_joint_indices_.size(); ++j)
00107         if (redundant_joint_indices_[j] == i)
00108         {
00109           skip = true;
00110           break;
00111         }
00112     if (skip)
00113       continue;
00114     jnt_array(i) = values[i];
00115   }
00116 }
00117 
00118 bool KDLKinematicsPlugin::checkConsistency(const KDL::JntArray& seed_state,
00119                                            const std::vector<double>& consistency_limits,
00120                                            const KDL::JntArray& solution) const
00121 {
00122   for (std::size_t i = 0; i < dimension_; ++i)
00123     if (fabs(seed_state(i) - solution(i)) > consistency_limits[i])
00124       return false;
00125   return true;
00126 }
00127 
00128 bool KDLKinematicsPlugin::initialize(const std::string& robot_description, const std::string& group_name,
00129                                      const std::string& base_frame, const std::string& tip_frame,
00130                                      double search_discretization)
00131 {
00132   setValues(robot_description, group_name, base_frame, tip_frame, search_discretization);
00133 
00134   ros::NodeHandle private_handle("~");
00135   rdf_loader::RDFLoader rdf_loader(robot_description_);
00136   const boost::shared_ptr<srdf::Model>& srdf = rdf_loader.getSRDF();
00137   const boost::shared_ptr<urdf::ModelInterface>& urdf_model = rdf_loader.getURDF();
00138 
00139   if (!urdf_model || !srdf)
00140   {
00141     ROS_ERROR_NAMED("kdl", "URDF and SRDF must be loaded for KDL kinematics solver to work.");
00142     return false;
00143   }
00144 
00145   robot_model_.reset(new robot_model::RobotModel(urdf_model, srdf));
00146 
00147   robot_model::JointModelGroup* joint_model_group = robot_model_->getJointModelGroup(group_name);
00148   if (!joint_model_group)
00149     return false;
00150 
00151   if (!joint_model_group->isChain())
00152   {
00153     ROS_ERROR_NAMED("kdl", "Group '%s' is not a chain", group_name.c_str());
00154     return false;
00155   }
00156   if (!joint_model_group->isSingleDOFJoints())
00157   {
00158     ROS_ERROR_NAMED("kdl", "Group '%s' includes joints that have more than 1 DOF", group_name.c_str());
00159     return false;
00160   }
00161 
00162   KDL::Tree kdl_tree;
00163 
00164   if (!kdl_parser::treeFromUrdfModel(*urdf_model, kdl_tree))
00165   {
00166     ROS_ERROR_NAMED("kdl", "Could not initialize tree object");
00167     return false;
00168   }
00169   if (!kdl_tree.getChain(base_frame_, getTipFrame(), kdl_chain_))
00170   {
00171     ROS_ERROR_NAMED("kdl", "Could not initialize chain object");
00172     return false;
00173   }
00174 
00175   dimension_ = joint_model_group->getActiveJointModels().size() + joint_model_group->getMimicJointModels().size();
00176   for (std::size_t i = 0; i < joint_model_group->getJointModels().size(); ++i)
00177   {
00178     if (joint_model_group->getJointModels()[i]->getType() == moveit::core::JointModel::REVOLUTE ||
00179         joint_model_group->getJointModels()[i]->getType() == moveit::core::JointModel::PRISMATIC)
00180     {
00181       ik_chain_info_.joint_names.push_back(joint_model_group->getJointModelNames()[i]);
00182       const std::vector<moveit_msgs::JointLimits>& jvec =
00183           joint_model_group->getJointModels()[i]->getVariableBoundsMsg();
00184       ik_chain_info_.limits.insert(ik_chain_info_.limits.end(), jvec.begin(), jvec.end());
00185     }
00186   }
00187 
00188   fk_chain_info_.joint_names = ik_chain_info_.joint_names;
00189   fk_chain_info_.limits = ik_chain_info_.limits;
00190 
00191   if (!joint_model_group->hasLinkModel(getTipFrame()))
00192   {
00193     ROS_ERROR_NAMED("kdl", "Could not find tip name in joint group '%s'", group_name.c_str());
00194     return false;
00195   }
00196   ik_chain_info_.link_names.push_back(getTipFrame());
00197   fk_chain_info_.link_names = joint_model_group->getLinkModelNames();
00198 
00199   joint_min_.resize(ik_chain_info_.limits.size());
00200   joint_max_.resize(ik_chain_info_.limits.size());
00201 
00202   for (unsigned int i = 0; i < ik_chain_info_.limits.size(); i++)
00203   {
00204     joint_min_(i) = ik_chain_info_.limits[i].min_position;
00205     joint_max_(i) = ik_chain_info_.limits[i].max_position;
00206   }
00207 
00208   // Get Solver Parameters
00209   int max_solver_iterations;
00210   double epsilon;
00211   bool position_ik;
00212 
00213   private_handle.param("max_solver_iterations", max_solver_iterations, 500);
00214   private_handle.param("epsilon", epsilon, 1e-5);
00215   private_handle.param(group_name + "/position_only_ik", position_ik, false);
00216   ROS_DEBUG_NAMED("kdl", "Looking in private handle: %s for param name: %s", private_handle.getNamespace().c_str(),
00217                   (group_name + "/position_only_ik").c_str());
00218 
00219   if (position_ik)
00220     ROS_INFO_NAMED("kdl", "Using position only ik");
00221 
00222   num_possible_redundant_joints_ =
00223       kdl_chain_.getNrOfJoints() - joint_model_group->getMimicJointModels().size() - (position_ik ? 3 : 6);
00224 
00225   // Check for mimic joints
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     // first check whether it belongs to the set of active joints in the group
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   // Setup the joint state groups that we need
00277   state_.reset(new robot_state::RobotState(robot_model_));
00278   state_2_.reset(new robot_state::RobotState(robot_model_));
00279 
00280   // Store things for when the set of redundant joints may change
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("kdl", "KDL solver initialized");
00288   return true;
00289 }
00290 
00291 bool KDLKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int>& redundant_joints)
00292 {
00293   if (num_possible_redundant_joints_ < 0)
00294   {
00295     ROS_ERROR_NAMED("kdl", "This group cannot have redundant joints");
00296     return false;
00297   }
00298   if (static_cast<int>(redundant_joints.size()) > num_possible_redundant_joints_)
00299   {
00300     ROS_ERROR_NAMED("kdl", "This group can only have %d redundant joints", num_possible_redundant_joints_);
00301     return false;
00302   }
00303   /*
00304     XmlRpc::XmlRpcValue joint_list;
00305     if(private_handle.getParam(group_name+"/redundant_joints", joint_list))
00306     {
00307       ROS_ASSERT(joint_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00308       std::vector<std::string> redundant_joints;
00309       for (std::size_t i = 0; i < joint_list.size(); ++i)
00310       {
00311         ROS_ASSERT(joint_list[i].getType() == XmlRpc::XmlRpcValue::TypeString);
00312         redundant_joints.push_back(static_cast<std::string>(joint_list[i]));
00313         ROS_INFO_NAMED("kdl","Designated joint: %s as redundant joint", redundant_joints.back().c_str());
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       // check for mimic
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("kdl", "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 KDLKinematicsPlugin::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 KDLKinematicsPlugin::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 KDLKinematicsPlugin::timedOut(const ros::WallTime& start_time, double duration) const
00374 {
00375   return ((ros::WallTime::now() - start_time).toSec() >= duration);
00376 }
00377 
00378 bool KDLKinematicsPlugin::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 KDLKinematicsPlugin::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 KDLKinematicsPlugin::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 KDLKinematicsPlugin::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 KDLKinematicsPlugin::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 KDLKinematicsPlugin::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("kdl", "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("kdl", "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("kdl", "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   KDL::ChainFkSolverPos_recursive fk_solver(kdl_chain_);
00468   KDL::ChainIkSolverVel_pinv_mimic ik_solver_vel(kdl_chain_, joint_model_group_->getMimicJointModels().size(),
00469                                                  redundant_joint_indices_.size(), position_ik_);
00470   KDL::ChainIkSolverPos_NR_JL_Mimic ik_solver_pos(kdl_chain_, joint_min_, joint_max_, fk_solver, ik_solver_vel,
00471                                                   max_solver_iterations_, epsilon_, position_ik_);
00472   ik_solver_vel.setMimicJoints(mimic_joints_);
00473   ik_solver_pos.setMimicJoints(mimic_joints_);
00474 
00475   if ((redundant_joint_indices_.size() > 0) && !ik_solver_vel.setRedundantJointsMapIndex(redundant_joints_map_index_))
00476   {
00477     ROS_ERROR_NAMED("kdl", "Could not set redundant joints");
00478     return false;
00479   }
00480 
00481   if (options.lock_redundant_joints)
00482   {
00483     ik_solver_vel.lockRedundantJoints();
00484   }
00485 
00486   solution.resize(dimension_);
00487 
00488   KDL::Frame pose_desired;
00489   tf::poseMsgToKDL(ik_pose, pose_desired);
00490 
00491   ROS_DEBUG_STREAM_NAMED("kdl", "searchPositionIK2: Position request pose is "
00492                                     << ik_pose.position.x << " " << ik_pose.position.y << " " << ik_pose.position.z
00493                                     << " " << ik_pose.orientation.x << " " << ik_pose.orientation.y << " "
00494                                     << ik_pose.orientation.z << " " << ik_pose.orientation.w);
00495   // Do the IK
00496   for (unsigned int i = 0; i < dimension_; i++)
00497     jnt_seed_state(i) = ik_seed_state[i];
00498   jnt_pos_in = jnt_seed_state;
00499 
00500   unsigned int counter(0);
00501   while (1)
00502   {
00503     //    ROS_DEBUG_NAMED("kdl","Iteration: %d, time: %f, Timeout:
00504     //    %f",counter,(ros::WallTime::now()-n1).toSec(),timeout);
00505     counter++;
00506     if (timedOut(n1, timeout))
00507     {
00508       ROS_DEBUG_NAMED("kdl", "IK timed out");
00509       error_code.val = error_code.TIMED_OUT;
00510       ik_solver_vel.unlockRedundantJoints();
00511       return false;
00512     }
00513     int ik_valid = ik_solver_pos.CartToJnt(jnt_pos_in, pose_desired, jnt_pos_out);
00514     ROS_DEBUG_NAMED("kdl", "IK valid: %d", ik_valid);
00515     if (!consistency_limits.empty())
00516     {
00517       getRandomConfiguration(jnt_seed_state, consistency_limits, jnt_pos_in, options.lock_redundant_joints);
00518       if ((ik_valid < 0 && !options.return_approximate_solution) ||
00519           !checkConsistency(jnt_seed_state, consistency_limits, jnt_pos_out))
00520       {
00521         ROS_DEBUG_NAMED("kdl", "Could not find IK solution: does not match consistency limits");
00522         continue;
00523       }
00524     }
00525     else
00526     {
00527       getRandomConfiguration(jnt_pos_in, options.lock_redundant_joints);
00528       ROS_DEBUG_NAMED("kdl", "New random configuration");
00529       for (unsigned int j = 0; j < dimension_; j++)
00530         ROS_DEBUG_NAMED("kdl", "%d %f", j, jnt_pos_in(j));
00531 
00532       if (ik_valid < 0 && !options.return_approximate_solution)
00533       {
00534         ROS_DEBUG_NAMED("kdl", "Could not find IK solution");
00535         continue;
00536       }
00537     }
00538     ROS_DEBUG_NAMED("kdl", "Found IK solution");
00539     for (unsigned int j = 0; j < dimension_; j++)
00540       solution[j] = jnt_pos_out(j);
00541     if (!solution_callback.empty())
00542       solution_callback(ik_pose, solution, error_code);
00543     else
00544       error_code.val = error_code.SUCCESS;
00545 
00546     if (error_code.val == error_code.SUCCESS)
00547     {
00548       ROS_DEBUG_STREAM_NAMED("kdl", "Solved after " << counter << " iterations");
00549       ik_solver_vel.unlockRedundantJoints();
00550       return true;
00551     }
00552   }
00553   ROS_DEBUG_NAMED("kdl", "An IK that satisifes the constraints and is collision free could not be found");
00554   error_code.val = error_code.NO_IK_SOLUTION;
00555   ik_solver_vel.unlockRedundantJoints();
00556   return false;
00557 }
00558 
00559 bool KDLKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
00560                                         const std::vector<double>& joint_angles,
00561                                         std::vector<geometry_msgs::Pose>& poses) const
00562 {
00563   ros::WallTime n1 = ros::WallTime::now();
00564   if (!active_)
00565   {
00566     ROS_ERROR_NAMED("kdl", "kinematics not active");
00567     return false;
00568   }
00569   poses.resize(link_names.size());
00570   if (joint_angles.size() != dimension_)
00571   {
00572     ROS_ERROR_NAMED("kdl", "Joint angles vector must have size: %d", dimension_);
00573     return false;
00574   }
00575 
00576   KDL::Frame p_out;
00577   geometry_msgs::PoseStamped pose;
00578   tf::Stamped<tf::Pose> tf_pose;
00579 
00580   KDL::JntArray jnt_pos_in(dimension_);
00581   for (unsigned int i = 0; i < dimension_; i++)
00582   {
00583     jnt_pos_in(i) = joint_angles[i];
00584   }
00585 
00586   KDL::ChainFkSolverPos_recursive fk_solver(kdl_chain_);
00587 
00588   bool valid = true;
00589   for (unsigned int i = 0; i < poses.size(); i++)
00590   {
00591     ROS_DEBUG_NAMED("kdl", "End effector index: %d", getKDLSegmentIndex(link_names[i]));
00592     if (fk_solver.JntToCart(jnt_pos_in, p_out, getKDLSegmentIndex(link_names[i])) >= 0)
00593     {
00594       tf::poseKDLToMsg(p_out, poses[i]);
00595     }
00596     else
00597     {
00598       ROS_ERROR_NAMED("kdl", "Could not compute FK for %s", link_names[i].c_str());
00599       valid = false;
00600     }
00601   }
00602   return valid;
00603 }
00604 
00605 const std::vector<std::string>& KDLKinematicsPlugin::getJointNames() const
00606 {
00607   return ik_chain_info_.joint_names;
00608 }
00609 
00610 const std::vector<std::string>& KDLKinematicsPlugin::getLinkNames() const
00611 {
00612   return ik_chain_info_.link_names;
00613 }
00614 
00615 }  // namespace


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Mon Jul 24 2017 02:21:29