nextage_left_arm_ikfast_moveit_plugin.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  * Copyright (c) 2013, Dave Coleman, CU Boulder; Jeremy Zoss, SwRI; David Butterworth, KAIST; Mathias Lüdtke, Fraunhofer IPA
00006  * All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *     * Redistributions of source code must retain the above copyright
00013  *       notice, this list of conditions and the following disclaimer.
00014  *     * Redistributions in binary form must reproduce the above copyright
00015  *       notice, this list of conditions and the following disclaimer in the
00016  *       documentation and/or other materials provided with the distribution.
00017  *     * Neither the name of the all of the author's companies nor the names of its
00018  *       contributors may be used to endorse or promote products derived from
00019  *       this software without specific prior written permission.
00020  *
00021  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00022  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00023  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00024  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00025  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00026  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00027  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00028  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00029  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00030  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031  * POSSIBILITY OF SUCH DAMAGE.
00032  *
00033  *********************************************************************/
00034 
00035 /*
00036  * IKFast Plugin Template for moveit
00037  *
00038  * AUTO-GENERATED by create_ikfast_moveit_plugin.py in arm_kinematics_tools
00039  * You should run create_ikfast_moveit_plugin.py to generate your own plugin.
00040  *
00041  * Creates a kinematics plugin using the output of IKFast from OpenRAVE.
00042  * This plugin and the move_group node can be used as a general
00043  * kinematics service, from within the moveit planning environment, or in
00044  * your own ROS node.
00045  *
00046  */
00047 
00048 #include <ros/ros.h>
00049 #include <moveit/kinematics_base/kinematics_base.h>
00050 #include <urdf/model.h>
00051 #include <tf_conversions/tf_kdl.h>
00052 
00053 // Need a floating point tolerance when checking joint limits, in case the joint starts at limit
00054 const double LIMIT_TOLERANCE = .0000001;
00056 enum SEARCH_MODE { OPTIMIZE_FREE_JOINT=1, OPTIMIZE_MAX_JOINT=2 };
00057 
00058 namespace nextage_left_arm_ikfast_kinematics_plugin
00059 {
00060 
00061 #define IKFAST_NO_MAIN // Don't include main() from IKFast
00062 
00068 enum IkParameterizationType {
00069     IKP_None=0,
00070     IKP_Transform6D=0x67000001,     
00071     IKP_Rotation3D=0x34000002,     
00072     IKP_Translation3D=0x33000003,     
00073     IKP_Direction3D=0x23000004,     
00074     IKP_Ray4D=0x46000005,     
00075     IKP_Lookat3D=0x23000006,     
00076     IKP_TranslationDirection5D=0x56000007,     
00077     IKP_TranslationXY2D=0x22000008,     
00078     IKP_TranslationXYOrientation3D=0x33000009,     
00079     IKP_TranslationLocalGlobal6D=0x3600000a,     
00080 
00081     IKP_TranslationXAxisAngle4D=0x4400000b, 
00082     IKP_TranslationYAxisAngle4D=0x4400000c, 
00083     IKP_TranslationZAxisAngle4D=0x4400000d, 
00084 
00085     IKP_TranslationXAxisAngleZNorm4D=0x4400000e, 
00086     IKP_TranslationYAxisAngleXNorm4D=0x4400000f, 
00087     IKP_TranslationZAxisAngleYNorm4D=0x44000010, 
00088 
00089     IKP_NumberOfParameterizations=16,     
00090 
00091     IKP_VelocityDataBit = 0x00008000, 
00092     IKP_Transform6DVelocity = IKP_Transform6D|IKP_VelocityDataBit,
00093     IKP_Rotation3DVelocity = IKP_Rotation3D|IKP_VelocityDataBit,
00094     IKP_Translation3DVelocity = IKP_Translation3D|IKP_VelocityDataBit,
00095     IKP_Direction3DVelocity = IKP_Direction3D|IKP_VelocityDataBit,
00096     IKP_Ray4DVelocity = IKP_Ray4D|IKP_VelocityDataBit,
00097     IKP_Lookat3DVelocity = IKP_Lookat3D|IKP_VelocityDataBit,
00098     IKP_TranslationDirection5DVelocity = IKP_TranslationDirection5D|IKP_VelocityDataBit,
00099     IKP_TranslationXY2DVelocity = IKP_TranslationXY2D|IKP_VelocityDataBit,
00100     IKP_TranslationXYOrientation3DVelocity = IKP_TranslationXYOrientation3D|IKP_VelocityDataBit,
00101     IKP_TranslationLocalGlobal6DVelocity = IKP_TranslationLocalGlobal6D|IKP_VelocityDataBit,
00102     IKP_TranslationXAxisAngle4DVelocity = IKP_TranslationXAxisAngle4D|IKP_VelocityDataBit,
00103     IKP_TranslationYAxisAngle4DVelocity = IKP_TranslationYAxisAngle4D|IKP_VelocityDataBit,
00104     IKP_TranslationZAxisAngle4DVelocity = IKP_TranslationZAxisAngle4D|IKP_VelocityDataBit,
00105     IKP_TranslationXAxisAngleZNorm4DVelocity = IKP_TranslationXAxisAngleZNorm4D|IKP_VelocityDataBit,
00106     IKP_TranslationYAxisAngleXNorm4DVelocity = IKP_TranslationYAxisAngleXNorm4D|IKP_VelocityDataBit,
00107     IKP_TranslationZAxisAngleYNorm4DVelocity = IKP_TranslationZAxisAngleYNorm4D|IKP_VelocityDataBit,
00108 
00109     IKP_UniqueIdMask = 0x0000ffff, 
00110     IKP_CustomDataBit = 0x00010000, 
00111 };
00112 
00113 // Code generated by IKFast56/61
00114 #include "nextage_left_arm_ikfast_solver.cpp"
00115 
00116 class IKFastKinematicsPlugin : public kinematics::KinematicsBase
00117 {
00118   std::vector<std::string> joint_names_;
00119   std::vector<double> joint_min_vector_;
00120   std::vector<double> joint_max_vector_;
00121   std::vector<bool> joint_has_limits_vector_;
00122   std::vector<std::string> link_names_;
00123   size_t num_joints_;
00124   std::vector<int> free_params_;
00125   bool active_; // Internal variable that indicates whether solvers are configured and ready
00126 
00127   const std::vector<std::string>& getJointNames() const { return joint_names_; }
00128   const std::vector<std::string>& getLinkNames() const { return link_names_; }
00129 
00130 public:
00131 
00135   IKFastKinematicsPlugin():active_(false){}
00136 
00146   // Returns the first IK solution that is within joint limits, this is called by get_ik() service
00147   bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00148                      const std::vector<double> &ik_seed_state,
00149                      std::vector<double> &solution,
00150                      moveit_msgs::MoveItErrorCodes &error_code,
00151                      const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00152 
00161   bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00162                         const std::vector<double> &ik_seed_state,
00163                         double timeout,
00164                         std::vector<double> &solution,
00165                         moveit_msgs::MoveItErrorCodes &error_code,
00166                         const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00167 
00177   bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00178                         const std::vector<double> &ik_seed_state,
00179                         double timeout,
00180                         const std::vector<double> &consistency_limits,
00181                         std::vector<double> &solution,
00182                         moveit_msgs::MoveItErrorCodes &error_code,
00183                         const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00184 
00193   bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00194                         const std::vector<double> &ik_seed_state,
00195                         double timeout,
00196                         std::vector<double> &solution,
00197                         const IKCallbackFn &solution_callback,
00198                         moveit_msgs::MoveItErrorCodes &error_code,
00199                         const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00200 
00211   bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00212                         const std::vector<double> &ik_seed_state,
00213                         double timeout,
00214                         const std::vector<double> &consistency_limits,
00215                         std::vector<double> &solution,
00216                         const IKCallbackFn &solution_callback,
00217                         moveit_msgs::MoveItErrorCodes &error_code,
00218                         const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00219 
00231   bool getPositionFK(const std::vector<std::string> &link_names,
00232                      const std::vector<double> &joint_angles,
00233                      std::vector<geometry_msgs::Pose> &poses) const;
00234 
00235 private:
00236 
00237   bool initialize(const std::string &robot_description,
00238                   const std::string& group_name,
00239                   const std::string& base_name,
00240                   const std::string& tip_name,
00241                   double search_discretization);
00242 
00247   int solve(KDL::Frame &pose_frame, const std::vector<double> &vfree, IkSolutionList<IkReal> &solutions) const;
00248 
00252   void getSolution(const IkSolutionList<IkReal> &solutions, int i, std::vector<double>& solution) const;
00253 
00254   double harmonize(const std::vector<double> &ik_seed_state, std::vector<double> &solution) const;
00255   //void getOrderedSolutions(const std::vector<double> &ik_seed_state, std::vector<std::vector<double> >& solslist);
00256   void getClosestSolution(const IkSolutionList<IkReal> &solutions, const std::vector<double> &ik_seed_state, std::vector<double> &solution) const;
00257   void fillFreeParams(int count, int *array);
00258   bool getCount(int &count, const int &max_count, const int &min_count) const;
00259 
00260 }; // end class
00261 
00262 bool IKFastKinematicsPlugin::initialize(const std::string &robot_description,
00263                                         const std::string& group_name,
00264                                         const std::string& base_name,
00265                                         const std::string& tip_name,
00266                                         double search_discretization)
00267 {
00268   setValues(robot_description, group_name, base_name, tip_name, search_discretization);
00269 
00270   ros::NodeHandle node_handle("~/"+group_name);
00271 
00272   std::string robot;
00273   node_handle.param("robot",robot,std::string());
00274 
00275   // IKFast56/61
00276   fillFreeParams( GetNumFreeParameters(), GetFreeParameters() );
00277   num_joints_ = GetNumJoints();
00278 
00279   if(free_params_.size() > 1)
00280   {
00281     ROS_FATAL("Only one free joint paramter supported!");
00282     return false;
00283   }
00284 
00285   urdf::Model robot_model;
00286   std::string xml_string;
00287 
00288   std::string urdf_xml,full_urdf_xml;
00289   node_handle.param("urdf_xml",urdf_xml,robot_description);
00290   node_handle.searchParam(urdf_xml,full_urdf_xml);
00291 
00292   ROS_DEBUG_NAMED("ikfast","Reading xml file from parameter server");
00293   if (!node_handle.getParam(full_urdf_xml, xml_string))
00294   {
00295     ROS_FATAL_NAMED("ikfast","Could not load the xml from parameter server: %s", urdf_xml.c_str());
00296     return false;
00297   }
00298 
00299   node_handle.param(full_urdf_xml,xml_string,std::string());
00300   robot_model.initString(xml_string);
00301 
00302   ROS_DEBUG_STREAM_NAMED("ikfast","Reading joints and links from URDF");
00303 
00304   boost::shared_ptr<urdf::Link> link = boost::const_pointer_cast<urdf::Link>(robot_model.getLink(getTipFrame()));
00305   while(link->name != base_frame_ && joint_names_.size() <= num_joints_)
00306   {
00307     ROS_DEBUG_NAMED("ikfast","Link %s",link->name.c_str());
00308     link_names_.push_back(link->name);
00309     boost::shared_ptr<urdf::Joint> joint = link->parent_joint;
00310     if(joint)
00311     {
00312       if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
00313       {
00314         ROS_DEBUG_STREAM_NAMED("ikfast","Adding joint " << joint->name );
00315 
00316         joint_names_.push_back(joint->name);
00317         float lower, upper;
00318         int hasLimits;
00319         if ( joint->type != urdf::Joint::CONTINUOUS )
00320         {
00321           if(joint->safety)
00322           {
00323             lower = joint->safety->soft_lower_limit;
00324             upper = joint->safety->soft_upper_limit;
00325           } else {
00326             lower = joint->limits->lower;
00327             upper = joint->limits->upper;
00328           }
00329           hasLimits = 1;
00330         }
00331         else
00332         {
00333           lower = -M_PI;
00334           upper = M_PI;
00335           hasLimits = 0;
00336         }
00337         if(hasLimits)
00338         {
00339           joint_has_limits_vector_.push_back(true);
00340           joint_min_vector_.push_back(lower);
00341           joint_max_vector_.push_back(upper);
00342         }
00343         else
00344         {
00345           joint_has_limits_vector_.push_back(false);
00346           joint_min_vector_.push_back(-M_PI);
00347           joint_max_vector_.push_back(M_PI);
00348         }
00349       }
00350     } else
00351     {
00352       ROS_WARN_NAMED("ikfast","no joint corresponding to %s",link->name.c_str());
00353     }
00354     link = link->getParent();
00355   }
00356 
00357   if(joint_names_.size() != num_joints_)
00358   {
00359     ROS_FATAL_STREAM_NAMED("ikfast","Joint numbers mismatch: URDF has " << joint_names_.size() << " and IKFast has " << num_joints_);
00360     return false;
00361   }
00362 
00363   std::reverse(link_names_.begin(),link_names_.end());
00364   std::reverse(joint_names_.begin(),joint_names_.end());
00365   std::reverse(joint_min_vector_.begin(),joint_min_vector_.end());
00366   std::reverse(joint_max_vector_.begin(),joint_max_vector_.end());
00367   std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end());
00368 
00369   for(size_t i=0; i <num_joints_; ++i)
00370     ROS_INFO_STREAM_NAMED("ikfast",joint_names_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i] << " " << joint_has_limits_vector_[i]);
00371 
00372   active_ = true;
00373   return true;
00374 }
00375 
00376 int IKFastKinematicsPlugin::solve(KDL::Frame &pose_frame, const std::vector<double> &vfree, IkSolutionList<IkReal> &solutions) const
00377 {
00378   // IKFast56/61
00379   solutions.Clear();
00380 
00381   double trans[3];
00382   trans[0] = pose_frame.p[0];//-.18;
00383   trans[1] = pose_frame.p[1];
00384   trans[2] = pose_frame.p[2];
00385 
00386   KDL::Rotation mult;
00387   KDL::Vector direction;
00388 
00389   switch (GetIkType())
00390   {
00391     case IKP_Transform6D:
00392     case IKP_Translation3D:
00393       // For **Transform6D**, eerot is 9 values for the 3x3 rotation matrix. For **Translation3D**, these are ignored.
00394 
00395       mult = pose_frame.M;
00396 
00397       double vals[9];
00398       vals[0] = mult(0,0);
00399       vals[1] = mult(0,1);
00400       vals[2] = mult(0,2);
00401       vals[3] = mult(1,0);
00402       vals[4] = mult(1,1);
00403       vals[5] = mult(1,2);
00404       vals[6] = mult(2,0);
00405       vals[7] = mult(2,1);
00406       vals[8] = mult(2,2);
00407 
00408       // IKFast56/61
00409       ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
00410       return solutions.GetNumSolutions();
00411 
00412     case IKP_Direction3D:
00413     case IKP_Ray4D:
00414     case IKP_TranslationDirection5D:
00415       // For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target direction.
00416 
00417       direction = pose_frame.M * KDL::Vector(0, 0, 1);
00418       ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
00419       return solutions.GetNumSolutions();
00420 
00421     case IKP_TranslationXAxisAngle4D:
00422     case IKP_TranslationYAxisAngle4D:
00423     case IKP_TranslationZAxisAngle4D:
00424       // For **TranslationXAxisAngle4D**, **TranslationYAxisAngle4D**, and **TranslationZAxisAngle4D**, the first value represents the angle.
00425       ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
00426       return 0;
00427 
00428     case IKP_TranslationLocalGlobal6D:
00429       // For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end effector coordinate system.
00430       ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
00431       return 0;
00432 
00433     case IKP_Rotation3D:
00434     case IKP_Lookat3D:
00435     case IKP_TranslationXY2D:
00436     case IKP_TranslationXYOrientation3D:
00437     case IKP_TranslationXAxisAngleZNorm4D:
00438     case IKP_TranslationYAxisAngleXNorm4D:
00439     case IKP_TranslationZAxisAngleYNorm4D:
00440       ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
00441       return 0;
00442 
00443     default:
00444       ROS_ERROR_NAMED("ikfast", "Unknown IkParameterizationType! Was the solver generated with an incompatible version of Openrave?");
00445       return 0;
00446   }
00447 }
00448 
00449 void IKFastKinematicsPlugin::getSolution(const IkSolutionList<IkReal> &solutions, int i, std::vector<double>& solution) const
00450 {
00451   solution.clear();
00452   solution.resize(num_joints_);
00453 
00454   // IKFast56/61
00455   const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
00456   std::vector<IkReal> vsolfree( sol.GetFree().size() );
00457   sol.GetSolution(&solution[0],vsolfree.size()>0?&vsolfree[0]:NULL);
00458 
00459   // std::cout << "solution " << i << ":" ;
00460   // for(int j=0;j<num_joints_; ++j)
00461   //   std::cout << " " << solution[j];
00462   // std::cout << std::endl;
00463 
00464   //ROS_ERROR("%f %d",solution[2],vsolfree.size());
00465 }
00466 
00467 double IKFastKinematicsPlugin::harmonize(const std::vector<double> &ik_seed_state, std::vector<double> &solution) const
00468 {
00469   double dist_sqr = 0;
00470   std::vector<double> ss = ik_seed_state;
00471   for(size_t i=0; i< ik_seed_state.size(); ++i)
00472   {
00473     while(ss[i] > 2*M_PI) {
00474       ss[i] -= 2*M_PI;
00475     }
00476     while(ss[i] < 2*M_PI) {
00477       ss[i] += 2*M_PI;
00478     }
00479     while(solution[i] > 2*M_PI) {
00480       solution[i] -= 2*M_PI;
00481     }
00482     while(solution[i] < 2*M_PI) {
00483       solution[i] += 2*M_PI;
00484     }
00485     dist_sqr += fabs(ik_seed_state[i] - solution[i]);
00486   }
00487   return dist_sqr;
00488 }
00489 
00490 // void IKFastKinematicsPlugin::getOrderedSolutions(const std::vector<double> &ik_seed_state,
00491 //                                  std::vector<std::vector<double> >& solslist)
00492 // {
00493 //   std::vector<double>
00494 //   double mindist = 0;
00495 //   int minindex = -1;
00496 //   std::vector<double> sol;
00497 //   for(size_t i=0;i<solslist.size();++i){
00498 //     getSolution(i,sol);
00499 //     double dist = harmonize(ik_seed_state, sol);
00500 //     //std::cout << "dist[" << i << "]= " << dist << std::endl;
00501 //     if(minindex == -1 || dist<mindist){
00502 //       minindex = i;
00503 //       mindist = dist;
00504 //     }
00505 //   }
00506 //   if(minindex >= 0){
00507 //     getSolution(minindex,solution);
00508 //     harmonize(ik_seed_state, solution);
00509 //     index = minindex;
00510 //   }
00511 // }
00512 
00513 void IKFastKinematicsPlugin::getClosestSolution(const IkSolutionList<IkReal> &solutions, const std::vector<double> &ik_seed_state, std::vector<double> &solution) const
00514 {
00515   double mindist = DBL_MAX;
00516   int minindex = -1;
00517   std::vector<double> sol;
00518 
00519   // IKFast56/61
00520   for(size_t i=0; i < solutions.GetNumSolutions(); ++i)
00521   {
00522     getSolution(solutions, i,sol);
00523     double dist = harmonize(ik_seed_state, sol);
00524     ROS_INFO_STREAM_NAMED("ikfast","Dist " << i << " dist " << dist);
00525     //std::cout << "dist[" << i << "]= " << dist << std::endl;
00526     if(minindex == -1 || dist<mindist){
00527       minindex = i;
00528       mindist = dist;
00529     }
00530   }
00531   if(minindex >= 0){
00532     getSolution(solutions, minindex,solution);
00533     harmonize(ik_seed_state, solution);
00534   }
00535 }
00536 
00537 void IKFastKinematicsPlugin::fillFreeParams(int count, int *array)
00538 {
00539   free_params_.clear();
00540   for(int i=0; i<count;++i) free_params_.push_back(array[i]);
00541 }
00542 
00543 bool IKFastKinematicsPlugin::getCount(int &count, const int &max_count, const int &min_count) const
00544 {
00545   if(count > 0)
00546   {
00547     if(-count >= min_count)
00548     {
00549       count = -count;
00550       return true;
00551     }
00552     else if(count+1 <= max_count)
00553     {
00554       count = count+1;
00555       return true;
00556     }
00557     else
00558     {
00559       return false;
00560     }
00561   }
00562   else
00563   {
00564     if(1-count <= max_count)
00565     {
00566       count = 1-count;
00567       return true;
00568     }
00569     else if(count-1 >= min_count)
00570     {
00571       count = count -1;
00572       return true;
00573     }
00574     else
00575       return false;
00576   }
00577 }
00578 
00579 bool IKFastKinematicsPlugin::getPositionFK(const std::vector<std::string> &link_names,
00580                                            const std::vector<double> &joint_angles,
00581                                            std::vector<geometry_msgs::Pose> &poses) const
00582 {
00583   if (GetIkType() != IKP_Transform6D) {
00584     ROS_ERROR_NAMED("ikfast", "Can only compute FK for IKTYPE_TRANSFORM_6D!");
00585     return false;
00586   }
00587 
00588   KDL::Frame p_out;
00589   if(link_names.size() == 0) {
00590     ROS_WARN_STREAM_NAMED("ikfast","Link names with nothing");
00591     return false;
00592   }
00593 
00594   if(link_names.size()!=1 || link_names[0]!=getTipFrame()){
00595     ROS_ERROR_NAMED("ikfast","Can compute FK for %s only",getTipFrame().c_str());
00596     return false;
00597   }
00598 
00599   bool valid = true;
00600 
00601   IkReal eerot[9],eetrans[3];
00602   IkReal angles[joint_angles.size()];
00603   for (unsigned char i=0; i < joint_angles.size(); i++)
00604     angles[i] = joint_angles[i];
00605 
00606   // IKFast56/61
00607   ComputeFk(angles,eetrans,eerot);
00608 
00609   for(int i=0; i<3;++i)
00610     p_out.p.data[i] = eetrans[i];
00611 
00612   for(int i=0; i<9;++i)
00613     p_out.M.data[i] = eerot[i];
00614 
00615   poses.resize(1);
00616   tf::poseKDLToMsg(p_out,poses[0]);
00617 
00618   return valid;
00619 }
00620 
00621 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00622                                            const std::vector<double> &ik_seed_state,
00623                                            double timeout,
00624                                            std::vector<double> &solution,
00625                                            moveit_msgs::MoveItErrorCodes &error_code,
00626                                            const kinematics::KinematicsQueryOptions &options) const
00627 {
00628   const IKCallbackFn solution_callback = 0; 
00629   std::vector<double> consistency_limits;
00630 
00631   return searchPositionIK(ik_pose,
00632                           ik_seed_state,
00633                           timeout,
00634                           consistency_limits,
00635                           solution,
00636                           solution_callback,
00637                           error_code,
00638                           options);
00639 }
00640     
00641 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00642                                            const std::vector<double> &ik_seed_state,
00643                                            double timeout,
00644                                            const std::vector<double> &consistency_limits,
00645                                            std::vector<double> &solution,
00646                                            moveit_msgs::MoveItErrorCodes &error_code,
00647                                            const kinematics::KinematicsQueryOptions &options) const
00648 {
00649   const IKCallbackFn solution_callback = 0; 
00650   return searchPositionIK(ik_pose,
00651                           ik_seed_state,
00652                           timeout,
00653                           consistency_limits,
00654                           solution,
00655                           solution_callback,
00656                           error_code,
00657                           options);
00658 }
00659 
00660 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00661                                            const std::vector<double> &ik_seed_state,
00662                                            double timeout,
00663                                            std::vector<double> &solution,
00664                                            const IKCallbackFn &solution_callback,
00665                                            moveit_msgs::MoveItErrorCodes &error_code,
00666                                            const kinematics::KinematicsQueryOptions &options) const
00667 {
00668   std::vector<double> consistency_limits;
00669   return searchPositionIK(ik_pose,
00670                           ik_seed_state,
00671                           timeout,
00672                           consistency_limits,
00673                           solution,
00674                           solution_callback,
00675                           error_code,
00676                           options);
00677 }
00678 
00679 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00680                                               const std::vector<double> &ik_seed_state,
00681                                               double timeout,
00682                                               const std::vector<double> &consistency_limits,
00683                                               std::vector<double> &solution,
00684                                               const IKCallbackFn &solution_callback,
00685                                               moveit_msgs::MoveItErrorCodes &error_code,
00686                                               const kinematics::KinematicsQueryOptions &options) const
00687 {
00688   ROS_DEBUG_STREAM_NAMED("ikfast","searchPositionIK");
00689 
00691   SEARCH_MODE search_mode = OPTIMIZE_MAX_JOINT;
00692 
00693   // Check if there are no redundant joints
00694   if(free_params_.size()==0)
00695   {
00696     ROS_DEBUG_STREAM_NAMED("ikfast","No need to search since no free params/redundant joints");
00697 
00698     // Find first IK solution, within joint limits
00699     if(!getPositionIK(ik_pose, ik_seed_state, solution, error_code))
00700     {
00701       ROS_DEBUG_STREAM_NAMED("ikfast","No solution whatsoever");
00702       error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
00703       return false;
00704     }
00705 
00706     // check for collisions if a callback is provided
00707     if( !solution_callback.empty() )
00708     {
00709       solution_callback(ik_pose, solution, error_code);
00710       if(error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
00711       {
00712         ROS_DEBUG_STREAM_NAMED("ikfast","Solution passes callback");
00713         return true;
00714       }
00715       else
00716       {
00717         ROS_DEBUG_STREAM_NAMED("ikfast","Solution has error code " << error_code);
00718         return false;
00719       }
00720     }
00721     else
00722     {
00723       return true; // no collision check callback provided
00724     }
00725   }
00726 
00727   // -------------------------------------------------------------------------------------------------
00728   // Error Checking
00729   if(!active_)
00730   {
00731     ROS_ERROR_STREAM_NAMED("ikfast","Kinematics not active");
00732     error_code.val = error_code.NO_IK_SOLUTION;
00733     return false;
00734   }
00735 
00736   if(ik_seed_state.size() != num_joints_)
00737   {
00738     ROS_ERROR_STREAM_NAMED("ikfast","Seed state must have size " << num_joints_ << " instead of size " << ik_seed_state.size());
00739     error_code.val = error_code.NO_IK_SOLUTION;
00740     return false;
00741   }
00742 
00743   if(!consistency_limits.empty() && consistency_limits.size() != num_joints_)
00744   {
00745     ROS_ERROR_STREAM_NAMED("ikfast","Consistency limits be empty or must have size " << num_joints_ << " instead of size " << consistency_limits.size());
00746     error_code.val = error_code.NO_IK_SOLUTION;
00747     return false;
00748   }
00749 
00750 
00751   // -------------------------------------------------------------------------------------------------
00752   // Initialize
00753 
00754   KDL::Frame frame;
00755   tf::poseMsgToKDL(ik_pose,frame);
00756 
00757   std::vector<double> vfree(free_params_.size());
00758 
00759   ros::Time maxTime = ros::Time::now() + ros::Duration(timeout);
00760   int counter = 0;
00761 
00762   double initial_guess = ik_seed_state[free_params_[0]];
00763   vfree[0] = initial_guess;
00764 
00765   // -------------------------------------------------------------------------------------------------
00766   // Handle consitency limits if needed
00767   int num_positive_increments;
00768   int num_negative_increments;
00769 
00770   if(!consistency_limits.empty())
00771   {
00772     // moveit replaced consistency_limit (scalar) w/ consistency_limits (vector)
00773     // Assume [0]th free_params element for now.  Probably wrong.
00774     double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess+consistency_limits[free_params_[0]]);
00775     double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess-consistency_limits[free_params_[0]]);
00776 
00777     num_positive_increments = (int)((max_limit-initial_guess)/search_discretization_);
00778     num_negative_increments = (int)((initial_guess-min_limit)/search_discretization_);
00779   }
00780   else // no consitency limits provided
00781   {
00782     num_positive_increments = (joint_max_vector_[free_params_[0]]-initial_guess)/search_discretization_;
00783     num_negative_increments = (initial_guess-joint_min_vector_[free_params_[0]])/search_discretization_;
00784   }
00785 
00786   // -------------------------------------------------------------------------------------------------
00787   // Begin searching
00788 
00789   ROS_DEBUG_STREAM_NAMED("ikfast","Free param is " << free_params_[0] << " initial guess is " << initial_guess << ", # positive increments: " << num_positive_increments << ", # negative increments: " << num_negative_increments);
00790   if ((search_mode & OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000)
00791       ROS_WARN_STREAM_ONCE_NAMED("ikfast", "Large search space, consider increasing the search discretization");
00792   
00793   double best_costs = -1.0;
00794   std::vector<double> best_solution;
00795   int nattempts = 0, nvalid = 0;
00796 
00797   while(true)
00798   {
00799     IkSolutionList<IkReal> solutions;
00800     int numsol = solve(frame,vfree, solutions);
00801 
00802     ROS_DEBUG_STREAM_NAMED("ikfast","Found " << numsol << " solutions from IKFast");
00803 
00804     //ROS_INFO("%f",vfree[0]);
00805 
00806     if( numsol > 0 )
00807     {
00808       for(int s = 0; s < numsol; ++s)
00809       {
00810         nattempts++;
00811         std::vector<double> sol;
00812         getSolution(solutions,s,sol);
00813 
00814         bool obeys_limits = true;
00815         for(unsigned int i = 0; i < sol.size(); i++)
00816         {
00817           if(joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
00818           {
00819             obeys_limits = false;
00820             break;
00821           }
00822           //ROS_INFO_STREAM_NAMED("ikfast","Num " << i << " value " << sol[i] << " has limits " << joint_has_limits_vector_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i]);
00823         }
00824         if(obeys_limits)
00825         {
00826           getSolution(solutions,s,solution);
00827 
00828           // This solution is within joint limits, now check if in collision (if callback provided)
00829           if(!solution_callback.empty())
00830           {
00831             solution_callback(ik_pose, solution, error_code);
00832           }
00833           else
00834           {
00835             error_code.val = error_code.SUCCESS;
00836           }
00837 
00838           if(error_code.val == error_code.SUCCESS)
00839           {
00840             nvalid++;
00841             if (search_mode & OPTIMIZE_MAX_JOINT)
00842             {
00843               // Costs for solution: Largest joint motion
00844               double costs = 0.0;
00845               for(unsigned int i = 0; i < solution.size(); i++)
00846               {
00847                 double d = fabs(ik_seed_state[i] - solution[i]);
00848                 if (d > costs)
00849                   costs = d;
00850               }
00851               if (costs < best_costs || best_costs == -1.0)
00852               {
00853                 best_costs = costs;
00854                 best_solution = solution;
00855               }
00856             }
00857             else
00858               // Return first feasible solution
00859               return true;
00860           }
00861         }
00862       }
00863     }
00864 
00865     if(!getCount(counter, num_positive_increments, -num_negative_increments))
00866     {
00867       // Everything searched
00868       error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
00869       break;
00870     }
00871 
00872     vfree[0] = initial_guess+search_discretization_*counter;
00873     //ROS_DEBUG_STREAM_NAMED("ikfast","Attempt " << counter << " with 0th free joint having value " << vfree[0]);
00874   }
00875 
00876   ROS_DEBUG_STREAM_NAMED("ikfast", "Valid solutions: " << nvalid << "/" << nattempts);
00877 
00878   if ((search_mode & OPTIMIZE_MAX_JOINT) && best_costs != -1.0)
00879   {
00880     solution = best_solution;
00881     error_code.val = error_code.SUCCESS;
00882     return true;
00883   }
00884 
00885   // No solution found
00886   error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
00887   return false;
00888 }
00889 
00890 // Used when there are no redundant joints - aka no free params
00891 bool IKFastKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose,
00892                                            const std::vector<double> &ik_seed_state,
00893                                            std::vector<double> &solution,
00894                                            moveit_msgs::MoveItErrorCodes &error_code,
00895                                            const kinematics::KinematicsQueryOptions &options) const
00896 {
00897   ROS_DEBUG_STREAM_NAMED("ikfast","getPositionIK");
00898 
00899   if(!active_)
00900   {
00901     ROS_ERROR("kinematics not active");    
00902     return false;
00903   }
00904 
00905   std::vector<double> vfree(free_params_.size());
00906   for(std::size_t i = 0; i < free_params_.size(); ++i)
00907   {
00908     int p = free_params_[i];
00909     ROS_ERROR("%u is %f",p,ik_seed_state[p]);  // DTC
00910     vfree[i] = ik_seed_state[p];
00911   }
00912 
00913   KDL::Frame frame;
00914   tf::poseMsgToKDL(ik_pose,frame);
00915 
00916   IkSolutionList<IkReal> solutions;
00917   int numsol = solve(frame,vfree,solutions);
00918 
00919   ROS_DEBUG_STREAM_NAMED("ikfast","Found " << numsol << " solutions from IKFast");
00920 
00921   if(numsol)
00922   {
00923     for(int s = 0; s < numsol; ++s)
00924     {
00925       std::vector<double> sol;
00926       getSolution(solutions,s,sol);
00927       ROS_DEBUG_NAMED("ikfast","Sol %d: %e   %e   %e   %e   %e   %e", s, sol[0], sol[1], sol[2], sol[3], sol[4], sol[5]);
00928 
00929       bool obeys_limits = true;
00930       for(unsigned int i = 0; i < sol.size(); i++)
00931       {
00932         // Add tolerance to limit check
00933         if(joint_has_limits_vector_[i] && ( (sol[i] < (joint_min_vector_[i]-LIMIT_TOLERANCE)) ||
00934                                             (sol[i] > (joint_max_vector_[i]+LIMIT_TOLERANCE)) ) )
00935         {
00936           // One element of solution is not within limits
00937           obeys_limits = false;
00938           ROS_DEBUG_STREAM_NAMED("ikfast","Not in limits! " << i << " value " << sol[i] << " has limit: " << joint_has_limits_vector_[i] << "  being  " << joint_min_vector_[i] << " to " << joint_max_vector_[i]);
00939           break;
00940         }
00941       }
00942       if(obeys_limits)
00943       {
00944         // All elements of solution obey limits
00945         getSolution(solutions,s,solution);
00946         error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00947         return true;
00948       }
00949     }
00950   }
00951   else
00952   {
00953     ROS_DEBUG_STREAM_NAMED("ikfast","No IK solution");
00954   }
00955 
00956   error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
00957   return false;
00958 }
00959 
00960 
00961 
00962 } // end namespace
00963 
00964 //register IKFastKinematicsPlugin as a KinematicsBase implementation
00965 #include <pluginlib/class_list_macros.h>
00966 PLUGINLIB_EXPORT_CLASS(nextage_left_arm_ikfast_kinematics_plugin::IKFastKinematicsPlugin, kinematics::KinematicsBase);


nextage_ik_plugin
Author(s): TORK Developer 534o <534o@opensouce-robotics.tokyo.jp>
autogenerated on Wed May 15 2019 04:45:04