fetch_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 #ifndef URDF_MODEL_TYPES_H
00059   // hacky, but older versions of urdf_model don't define types
00060   namespace urdf
00061   {
00062     typedef boost::shared_ptr<Link> LinkSharedPtr;
00063     typedef boost::shared_ptr<Joint> JointSharedPtr;
00064 
00065     template<class T, class U>
00066     boost::shared_ptr<T> const_pointer_cast(boost::shared_ptr<U> const & r)
00067     {
00068       return boost::const_pointer_cast<T>(r);
00069     }
00070   }
00071 #endif
00072 
00073 namespace ikfast_kinematics_plugin
00074 {
00075 
00076 #define IKFAST_NO_MAIN // Don't include main() from IKFast
00077 
00083 enum IkParameterizationType {
00084     IKP_None=0,
00085     IKP_Transform6D=0x67000001,     
00086     IKP_Rotation3D=0x34000002,     
00087     IKP_Translation3D=0x33000003,     
00088     IKP_Direction3D=0x23000004,     
00089     IKP_Ray4D=0x46000005,     
00090     IKP_Lookat3D=0x23000006,     
00091     IKP_TranslationDirection5D=0x56000007,     
00092     IKP_TranslationXY2D=0x22000008,     
00093     IKP_TranslationXYOrientation3D=0x33000009,     
00094     IKP_TranslationLocalGlobal6D=0x3600000a,     
00095 
00096     IKP_TranslationXAxisAngle4D=0x4400000b, 
00097     IKP_TranslationYAxisAngle4D=0x4400000c, 
00098     IKP_TranslationZAxisAngle4D=0x4400000d, 
00099 
00100     IKP_TranslationXAxisAngleZNorm4D=0x4400000e, 
00101     IKP_TranslationYAxisAngleXNorm4D=0x4400000f, 
00102     IKP_TranslationZAxisAngleYNorm4D=0x44000010, 
00103 
00104     IKP_NumberOfParameterizations=16,     
00105 
00106     IKP_VelocityDataBit = 0x00008000, 
00107     IKP_Transform6DVelocity = IKP_Transform6D|IKP_VelocityDataBit,
00108     IKP_Rotation3DVelocity = IKP_Rotation3D|IKP_VelocityDataBit,
00109     IKP_Translation3DVelocity = IKP_Translation3D|IKP_VelocityDataBit,
00110     IKP_Direction3DVelocity = IKP_Direction3D|IKP_VelocityDataBit,
00111     IKP_Ray4DVelocity = IKP_Ray4D|IKP_VelocityDataBit,
00112     IKP_Lookat3DVelocity = IKP_Lookat3D|IKP_VelocityDataBit,
00113     IKP_TranslationDirection5DVelocity = IKP_TranslationDirection5D|IKP_VelocityDataBit,
00114     IKP_TranslationXY2DVelocity = IKP_TranslationXY2D|IKP_VelocityDataBit,
00115     IKP_TranslationXYOrientation3DVelocity = IKP_TranslationXYOrientation3D|IKP_VelocityDataBit,
00116     IKP_TranslationLocalGlobal6DVelocity = IKP_TranslationLocalGlobal6D|IKP_VelocityDataBit,
00117     IKP_TranslationXAxisAngle4DVelocity = IKP_TranslationXAxisAngle4D|IKP_VelocityDataBit,
00118     IKP_TranslationYAxisAngle4DVelocity = IKP_TranslationYAxisAngle4D|IKP_VelocityDataBit,
00119     IKP_TranslationZAxisAngle4DVelocity = IKP_TranslationZAxisAngle4D|IKP_VelocityDataBit,
00120     IKP_TranslationXAxisAngleZNorm4DVelocity = IKP_TranslationXAxisAngleZNorm4D|IKP_VelocityDataBit,
00121     IKP_TranslationYAxisAngleXNorm4DVelocity = IKP_TranslationYAxisAngleXNorm4D|IKP_VelocityDataBit,
00122     IKP_TranslationZAxisAngleYNorm4DVelocity = IKP_TranslationZAxisAngleYNorm4D|IKP_VelocityDataBit,
00123 
00124     IKP_UniqueIdMask = 0x0000ffff, 
00125     IKP_CustomDataBit = 0x00010000, 
00126 };
00127 
00128 // Code generated by IKFast56/61
00129 #include "fetch_arm_ikfast_solver.cpp"
00130 
00131 class IKFastKinematicsPlugin : public kinematics::KinematicsBase
00132 {
00133   std::vector<std::string> joint_names_;
00134   std::vector<double> joint_min_vector_;
00135   std::vector<double> joint_max_vector_;
00136   std::vector<bool> joint_has_limits_vector_;
00137   std::vector<std::string> link_names_;
00138   size_t num_joints_;
00139   std::vector<int> free_params_;
00140   bool active_; // Internal variable that indicates whether solvers are configured and ready
00141 
00142   const std::vector<std::string>& getJointNames() const { return joint_names_; }
00143   const std::vector<std::string>& getLinkNames() const { return link_names_; }
00144 
00145 public:
00146 
00150   IKFastKinematicsPlugin():
00151     active_(false)
00152   {
00153     srand( time(NULL) );
00154     supported_methods_.push_back(kinematics::DiscretizationMethods::NO_DISCRETIZATION);
00155     supported_methods_.push_back(kinematics::DiscretizationMethods::ALL_DISCRETIZED);
00156     supported_methods_.push_back(kinematics::DiscretizationMethods::ALL_RANDOM_SAMPLED);
00157   }
00158 
00168   // Returns the first IK solution that is within joint limits, this is called by get_ik() service
00169   bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00170                      const std::vector<double> &ik_seed_state,
00171                      std::vector<double> &solution,
00172                      moveit_msgs::MoveItErrorCodes &error_code,
00173                      const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00174 
00190   bool getPositionIK(const std::vector<geometry_msgs::Pose> &ik_poses,
00191                              const std::vector<double> &ik_seed_state,
00192                              std::vector< std::vector<double> >& solutions,
00193                              kinematics::KinematicsResult& result,
00194                              const kinematics::KinematicsQueryOptions &options) const;
00195 
00204   bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00205                         const std::vector<double> &ik_seed_state,
00206                         double timeout,
00207                         std::vector<double> &solution,
00208                         moveit_msgs::MoveItErrorCodes &error_code,
00209                         const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00210 
00220   bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00221                         const std::vector<double> &ik_seed_state,
00222                         double timeout,
00223                         const std::vector<double> &consistency_limits,
00224                         std::vector<double> &solution,
00225                         moveit_msgs::MoveItErrorCodes &error_code,
00226                         const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00227 
00236   bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00237                         const std::vector<double> &ik_seed_state,
00238                         double timeout,
00239                         std::vector<double> &solution,
00240                         const IKCallbackFn &solution_callback,
00241                         moveit_msgs::MoveItErrorCodes &error_code,
00242                         const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00243 
00254   bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00255                         const std::vector<double> &ik_seed_state,
00256                         double timeout,
00257                         const std::vector<double> &consistency_limits,
00258                         std::vector<double> &solution,
00259                         const IKCallbackFn &solution_callback,
00260                         moveit_msgs::MoveItErrorCodes &error_code,
00261                         const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00262 
00271   bool getPositionFK(const std::vector<std::string> &link_names,
00272                      const std::vector<double> &joint_angles,
00273                      std::vector<geometry_msgs::Pose> &poses) const;
00274 
00275 
00284   void setSearchDiscretization(const std::map<int,double>& discretization);
00285 
00289   bool setRedundantJoints(const std::vector<unsigned int> &redundant_joint_indices);
00290 
00291 
00292 private:
00293 
00294   bool initialize(const std::string &robot_description,
00295                   const std::string& group_name,
00296                   const std::string& base_name,
00297                   const std::string& tip_name,
00298                   double search_discretization);
00299 
00304   int solve(KDL::Frame &pose_frame, const std::vector<double> &vfree, IkSolutionList<IkReal> &solutions) const;
00305 
00309   void getSolution(const IkSolutionList<IkReal> &solutions, int i, std::vector<double>& solution) const;
00310 
00311   double harmonize(const std::vector<double> &ik_seed_state, std::vector<double> &solution) const;
00312   //void getOrderedSolutions(const std::vector<double> &ik_seed_state, std::vector<std::vector<double> >& solslist);
00313   void getClosestSolution(const IkSolutionList<IkReal> &solutions, const std::vector<double> &ik_seed_state, std::vector<double> &solution) const;
00314   void fillFreeParams(int count, int *array);
00315   bool getCount(int &count, const int &max_count, const int &min_count) const;
00316 
00323   bool sampleRedundantJoint(kinematics::DiscretizationMethod method, std::vector<double>& sampled_joint_vals) const;
00324 
00325 }; // end class
00326 
00327 bool IKFastKinematicsPlugin::initialize(const std::string &robot_description,
00328                                         const std::string& group_name,
00329                                         const std::string& base_name,
00330                                         const std::string& tip_name,
00331                                         double search_discretization)
00332 {
00333   setValues(robot_description, group_name, base_name, tip_name, search_discretization);
00334 
00335   ros::NodeHandle node_handle("~/"+group_name);
00336 
00337   std::string robot;
00338   node_handle.param("robot",robot,std::string());
00339 
00340   // IKFast56/61
00341   fillFreeParams( GetNumFreeParameters(), GetFreeParameters() );
00342   num_joints_ = GetNumJoints();
00343 
00344   if(free_params_.size() > 1)
00345   {
00346     ROS_FATAL("Only one free joint parameter supported!");
00347     return false;
00348   }
00349   else if(free_params_.size() == 1)
00350   {
00351     redundant_joint_indices_.clear();
00352     redundant_joint_indices_.push_back(free_params_[0]);
00353     KinematicsBase::setSearchDiscretization(DEFAULT_SEARCH_DISCRETIZATION);
00354   }
00355 
00356   urdf::Model robot_model;
00357   std::string xml_string;
00358 
00359   std::string urdf_xml,full_urdf_xml;
00360   node_handle.param("urdf_xml",urdf_xml,robot_description);
00361   node_handle.searchParam(urdf_xml,full_urdf_xml);
00362 
00363   ROS_DEBUG_NAMED("ikfast","Reading xml file from parameter server");
00364   if (!node_handle.getParam(full_urdf_xml, xml_string))
00365   {
00366     ROS_FATAL_NAMED("ikfast","Could not load the xml from parameter server: %s", urdf_xml.c_str());
00367     return false;
00368   }
00369 
00370   node_handle.param(full_urdf_xml,xml_string,std::string());
00371   robot_model.initString(xml_string);
00372 
00373   ROS_DEBUG_STREAM_NAMED("ikfast","Reading joints and links from URDF");
00374 
00375   urdf::LinkSharedPtr link = urdf::const_pointer_cast<urdf::Link>(robot_model.getLink(getTipFrame()));
00376   while(link->name != base_frame_ && joint_names_.size() <= num_joints_)
00377   {
00378     ROS_DEBUG_NAMED("ikfast","Link %s",link->name.c_str());
00379     link_names_.push_back(link->name);
00380     urdf::JointSharedPtr joint = link->parent_joint;
00381     if(joint)
00382     {
00383       if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
00384       {
00385         ROS_DEBUG_STREAM_NAMED("ikfast","Adding joint " << joint->name );
00386 
00387         joint_names_.push_back(joint->name);
00388         float lower, upper;
00389         int hasLimits;
00390         if ( joint->type != urdf::Joint::CONTINUOUS )
00391         {
00392           if(joint->safety)
00393           {
00394             lower = joint->safety->soft_lower_limit;
00395             upper = joint->safety->soft_upper_limit;
00396           } else {
00397             lower = joint->limits->lower;
00398             upper = joint->limits->upper;
00399           }
00400           hasLimits = 1;
00401         }
00402         else
00403         {
00404           lower = -M_PI;
00405           upper = M_PI;
00406           hasLimits = 0;
00407         }
00408         if(hasLimits)
00409         {
00410           joint_has_limits_vector_.push_back(true);
00411           joint_min_vector_.push_back(lower);
00412           joint_max_vector_.push_back(upper);
00413         }
00414         else
00415         {
00416           joint_has_limits_vector_.push_back(false);
00417           joint_min_vector_.push_back(-M_PI);
00418           joint_max_vector_.push_back(M_PI);
00419         }
00420       }
00421     } else
00422     {
00423       ROS_WARN_NAMED("ikfast","no joint corresponding to %s",link->name.c_str());
00424     }
00425     link = link->getParent();
00426   }
00427 
00428   if(joint_names_.size() != num_joints_)
00429   {
00430     ROS_FATAL_STREAM_NAMED("ikfast","Joint numbers mismatch: URDF has " << joint_names_.size() << " and IKFast has " << num_joints_);
00431     return false;
00432   }
00433 
00434   std::reverse(link_names_.begin(),link_names_.end());
00435   std::reverse(joint_names_.begin(),joint_names_.end());
00436   std::reverse(joint_min_vector_.begin(),joint_min_vector_.end());
00437   std::reverse(joint_max_vector_.begin(),joint_max_vector_.end());
00438   std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end());
00439 
00440   for(size_t i=0; i <num_joints_; ++i)
00441     ROS_DEBUG_STREAM_NAMED("ikfast",joint_names_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i] << " " << joint_has_limits_vector_[i]);
00442 
00443   active_ = true;
00444   return true;
00445 }
00446 
00447 void IKFastKinematicsPlugin::setSearchDiscretization(const std::map<int,double>& discretization)
00448 {
00449 
00450   if(discretization.empty())
00451   {
00452     ROS_ERROR("The 'discretization' map is empty");
00453     return;
00454   }
00455 
00456   if(redundant_joint_indices_.empty())
00457   {
00458     ROS_ERROR_STREAM("This group's solver doesn't support redundant joints");
00459     return;
00460   }
00461 
00462   if(discretization.begin()->first != redundant_joint_indices_[0])
00463   {
00464     std::string redundant_joint = joint_names_[free_params_[0]];
00465     ROS_ERROR_STREAM("Attempted to discretize a non-redundant joint "<<discretization.begin()->first<<", only joint '"<<
00466                      redundant_joint<<"' with index " <<redundant_joint_indices_[0]<<" is redundant.");
00467     return;
00468   }
00469 
00470   if(discretization.begin()->second <= 0.0)
00471   {
00472           ROS_ERROR_STREAM("Discretization can not takes values that are <= 0");
00473           return;
00474   }
00475 
00476 
00477   redundant_joint_discretization_.clear();
00478   redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second;
00479 }
00480 
00481 bool IKFastKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int> &redundant_joint_indices)
00482 {
00483 
00484   ROS_ERROR_STREAM("Changing the redundant joints isn't permitted by this group's solver ");
00485   return false;
00486 }
00487 
00488 int IKFastKinematicsPlugin::solve(KDL::Frame &pose_frame, const std::vector<double> &vfree, IkSolutionList<IkReal> &solutions) const
00489 {
00490   // IKFast56/61
00491   solutions.Clear();
00492 
00493   double trans[3];
00494   trans[0] = pose_frame.p[0];//-.18;
00495   trans[1] = pose_frame.p[1];
00496   trans[2] = pose_frame.p[2];
00497 
00498   KDL::Rotation mult;
00499   KDL::Vector direction;
00500 
00501   switch (GetIkType())
00502   {
00503     case IKP_Transform6D:
00504     case IKP_Translation3D:
00505       // For **Transform6D**, eerot is 9 values for the 3x3 rotation matrix. For **Translation3D**, these are ignored.
00506 
00507       mult = pose_frame.M;
00508 
00509       double vals[9];
00510       vals[0] = mult(0,0);
00511       vals[1] = mult(0,1);
00512       vals[2] = mult(0,2);
00513       vals[3] = mult(1,0);
00514       vals[4] = mult(1,1);
00515       vals[5] = mult(1,2);
00516       vals[6] = mult(2,0);
00517       vals[7] = mult(2,1);
00518       vals[8] = mult(2,2);
00519 
00520       // IKFast56/61
00521       ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
00522       return solutions.GetNumSolutions();
00523 
00524     case IKP_Direction3D:
00525     case IKP_Ray4D:
00526     case IKP_TranslationDirection5D:
00527       // For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target direction.
00528 
00529       direction = pose_frame.M * KDL::Vector(0, 0, 1);
00530       ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
00531       return solutions.GetNumSolutions();
00532 
00533     case IKP_TranslationXAxisAngle4D:
00534     case IKP_TranslationYAxisAngle4D:
00535     case IKP_TranslationZAxisAngle4D:
00536       // For **TranslationXAxisAngle4D**, **TranslationYAxisAngle4D**, and **TranslationZAxisAngle4D**, the first value represents the angle.
00537       ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
00538       return 0;
00539 
00540     case IKP_TranslationLocalGlobal6D:
00541       // For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end effector coordinate system.
00542       ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
00543       return 0;
00544 
00545     case IKP_Rotation3D:
00546     case IKP_Lookat3D:
00547     case IKP_TranslationXY2D:
00548     case IKP_TranslationXYOrientation3D:
00549     case IKP_TranslationXAxisAngleZNorm4D:
00550     case IKP_TranslationYAxisAngleXNorm4D:
00551     case IKP_TranslationZAxisAngleYNorm4D:
00552       ROS_ERROR_NAMED("ikfast", "IK for this IkParameterizationType not implemented yet.");
00553       return 0;
00554 
00555     default:
00556       ROS_ERROR_NAMED("ikfast", "Unknown IkParameterizationType! Was the solver generated with an incompatible version of Openrave?");
00557       return 0;
00558   }
00559 }
00560 
00561 void IKFastKinematicsPlugin::getSolution(const IkSolutionList<IkReal> &solutions, int i, std::vector<double>& solution) const
00562 {
00563   solution.clear();
00564   solution.resize(num_joints_);
00565 
00566   // IKFast56/61
00567   const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
00568   std::vector<IkReal> vsolfree( sol.GetFree().size() );
00569   sol.GetSolution(&solution[0],vsolfree.size()>0?&vsolfree[0]:NULL);
00570 
00571   // std::cout << "solution " << i << ":" ;
00572   // for(int j=0;j<num_joints_; ++j)
00573   //   std::cout << " " << solution[j];
00574   // std::cout << std::endl;
00575 
00576   //ROS_ERROR("%f %d",solution[2],vsolfree.size());
00577 }
00578 
00579 double IKFastKinematicsPlugin::harmonize(const std::vector<double> &ik_seed_state, std::vector<double> &solution) const
00580 {
00581   double dist_sqr = 0;
00582   std::vector<double> ss = ik_seed_state;
00583   for(size_t i=0; i< ik_seed_state.size(); ++i)
00584   {
00585     while(ss[i] > 2*M_PI) {
00586       ss[i] -= 2*M_PI;
00587     }
00588     while(ss[i] < 2*M_PI) {
00589       ss[i] += 2*M_PI;
00590     }
00591     while(solution[i] > 2*M_PI) {
00592       solution[i] -= 2*M_PI;
00593     }
00594     while(solution[i] < 2*M_PI) {
00595       solution[i] += 2*M_PI;
00596     }
00597     dist_sqr += fabs(ik_seed_state[i] - solution[i]);
00598   }
00599   return dist_sqr;
00600 }
00601 
00602 // void IKFastKinematicsPlugin::getOrderedSolutions(const std::vector<double> &ik_seed_state,
00603 //                                  std::vector<std::vector<double> >& solslist)
00604 // {
00605 //   std::vector<double>
00606 //   double mindist = 0;
00607 //   int minindex = -1;
00608 //   std::vector<double> sol;
00609 //   for(size_t i=0;i<solslist.size();++i){
00610 //     getSolution(i,sol);
00611 //     double dist = harmonize(ik_seed_state, sol);
00612 //     //std::cout << "dist[" << i << "]= " << dist << std::endl;
00613 //     if(minindex == -1 || dist<mindist){
00614 //       minindex = i;
00615 //       mindist = dist;
00616 //     }
00617 //   }
00618 //   if(minindex >= 0){
00619 //     getSolution(minindex,solution);
00620 //     harmonize(ik_seed_state, solution);
00621 //     index = minindex;
00622 //   }
00623 // }
00624 
00625 void IKFastKinematicsPlugin::getClosestSolution(const IkSolutionList<IkReal> &solutions, const std::vector<double> &ik_seed_state, std::vector<double> &solution) const
00626 {
00627   double mindist = DBL_MAX;
00628   int minindex = -1;
00629   std::vector<double> sol;
00630 
00631   // IKFast56/61
00632   for(size_t i=0; i < solutions.GetNumSolutions(); ++i)
00633   {
00634     getSolution(solutions, i,sol);
00635     double dist = harmonize(ik_seed_state, sol);
00636     ROS_INFO_STREAM_NAMED("ikfast","Dist " << i << " dist " << dist);
00637     //std::cout << "dist[" << i << "]= " << dist << std::endl;
00638     if(minindex == -1 || dist<mindist){
00639       minindex = i;
00640       mindist = dist;
00641     }
00642   }
00643   if(minindex >= 0){
00644     getSolution(solutions, minindex,solution);
00645     harmonize(ik_seed_state, solution);
00646   }
00647 }
00648 
00649 void IKFastKinematicsPlugin::fillFreeParams(int count, int *array)
00650 {
00651   free_params_.clear();
00652   for(int i=0; i<count;++i) free_params_.push_back(array[i]);
00653 }
00654 
00655 bool IKFastKinematicsPlugin::getCount(int &count, const int &max_count, const int &min_count) const
00656 {
00657   if(count > 0)
00658   {
00659     if(-count >= min_count)
00660     {
00661       count = -count;
00662       return true;
00663     }
00664     else if(count+1 <= max_count)
00665     {
00666       count = count+1;
00667       return true;
00668     }
00669     else
00670     {
00671       return false;
00672     }
00673   }
00674   else
00675   {
00676     if(1-count <= max_count)
00677     {
00678       count = 1-count;
00679       return true;
00680     }
00681     else if(count-1 >= min_count)
00682     {
00683       count = count -1;
00684       return true;
00685     }
00686     else
00687       return false;
00688   }
00689 }
00690 
00691 bool IKFastKinematicsPlugin::getPositionFK(const std::vector<std::string> &link_names,
00692                                            const std::vector<double> &joint_angles,
00693                                            std::vector<geometry_msgs::Pose> &poses) const
00694 {
00695   if (GetIkType() != IKP_Transform6D) {
00696     // ComputeFk() is the inverse function of ComputeIk(), so the format of
00697     // eerot differs depending on IK type. The Transform6D IK type is the only
00698     // one for which a 3x3 rotation matrix is returned, which means we can only
00699     // compute FK for that IK type.
00700     ROS_ERROR_NAMED("ikfast", "Can only compute FK for Transform6D IK type!");
00701     return false;
00702   }
00703 
00704   KDL::Frame p_out;
00705   if(link_names.size() == 0) {
00706     ROS_WARN_STREAM_NAMED("ikfast","Link names with nothing");
00707     return false;
00708   }
00709 
00710   if(link_names.size()!=1 || link_names[0]!=getTipFrame()){
00711     ROS_ERROR_NAMED("ikfast","Can compute FK for %s only",getTipFrame().c_str());
00712     return false;
00713   }
00714 
00715   bool valid = true;
00716 
00717   IkReal eerot[9],eetrans[3];
00718   IkReal angles[joint_angles.size()];
00719   for (unsigned char i=0; i < joint_angles.size(); i++)
00720     angles[i] = joint_angles[i];
00721 
00722   // IKFast56/61
00723   ComputeFk(angles,eetrans,eerot);
00724 
00725   for(int i=0; i<3;++i)
00726     p_out.p.data[i] = eetrans[i];
00727 
00728   for(int i=0; i<9;++i)
00729     p_out.M.data[i] = eerot[i];
00730 
00731   poses.resize(1);
00732   tf::poseKDLToMsg(p_out,poses[0]);
00733 
00734   return valid;
00735 }
00736 
00737 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00738                                            const std::vector<double> &ik_seed_state,
00739                                            double timeout,
00740                                            std::vector<double> &solution,
00741                                            moveit_msgs::MoveItErrorCodes &error_code,
00742                                            const kinematics::KinematicsQueryOptions &options) const
00743 {
00744   const IKCallbackFn solution_callback = 0; 
00745   std::vector<double> consistency_limits;
00746 
00747   return searchPositionIK(ik_pose,
00748                           ik_seed_state,
00749                           timeout,
00750                           consistency_limits,
00751                           solution,
00752                           solution_callback,
00753                           error_code,
00754                           options);
00755 }
00756     
00757 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00758                                            const std::vector<double> &ik_seed_state,
00759                                            double timeout,
00760                                            const std::vector<double> &consistency_limits,
00761                                            std::vector<double> &solution,
00762                                            moveit_msgs::MoveItErrorCodes &error_code,
00763                                            const kinematics::KinematicsQueryOptions &options) const
00764 {
00765   const IKCallbackFn solution_callback = 0; 
00766   return searchPositionIK(ik_pose,
00767                           ik_seed_state,
00768                           timeout,
00769                           consistency_limits,
00770                           solution,
00771                           solution_callback,
00772                           error_code,
00773                           options);
00774 }
00775 
00776 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00777                                            const std::vector<double> &ik_seed_state,
00778                                            double timeout,
00779                                            std::vector<double> &solution,
00780                                            const IKCallbackFn &solution_callback,
00781                                            moveit_msgs::MoveItErrorCodes &error_code,
00782                                            const kinematics::KinematicsQueryOptions &options) const
00783 {
00784   std::vector<double> consistency_limits;
00785   return searchPositionIK(ik_pose,
00786                           ik_seed_state,
00787                           timeout,
00788                           consistency_limits,
00789                           solution,
00790                           solution_callback,
00791                           error_code,
00792                           options);
00793 }
00794 
00795 bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00796                                               const std::vector<double> &ik_seed_state,
00797                                               double timeout,
00798                                               const std::vector<double> &consistency_limits,
00799                                               std::vector<double> &solution,
00800                                               const IKCallbackFn &solution_callback,
00801                                               moveit_msgs::MoveItErrorCodes &error_code,
00802                                               const kinematics::KinematicsQueryOptions &options) const
00803 {
00804   ROS_DEBUG_STREAM_NAMED("ikfast","searchPositionIK");
00805 
00807   SEARCH_MODE search_mode = OPTIMIZE_MAX_JOINT;
00808 
00809   // Check if there are no redundant joints
00810   if(free_params_.size()==0)
00811   {
00812     ROS_DEBUG_STREAM_NAMED("ikfast","No need to search since no free params/redundant joints");
00813 
00814     // Find first IK solution, within joint limits
00815     if(!getPositionIK(ik_pose, ik_seed_state, solution, error_code))
00816     {
00817       ROS_DEBUG_STREAM_NAMED("ikfast","No solution whatsoever");
00818       error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
00819       return false;
00820     }
00821 
00822     // check for collisions if a callback is provided
00823     if( !solution_callback.empty() )
00824     {
00825       solution_callback(ik_pose, solution, error_code);
00826       if(error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
00827       {
00828         ROS_DEBUG_STREAM_NAMED("ikfast","Solution passes callback");
00829         return true;
00830       }
00831       else
00832       {
00833         ROS_DEBUG_STREAM_NAMED("ikfast","Solution has error code " << error_code);
00834         return false;
00835       }
00836     }
00837     else
00838     {
00839       return true; // no collision check callback provided
00840     }
00841   }
00842 
00843   // -------------------------------------------------------------------------------------------------
00844   // Error Checking
00845   if(!active_)
00846   {
00847     ROS_ERROR_STREAM_NAMED("ikfast","Kinematics not active");
00848     error_code.val = error_code.NO_IK_SOLUTION;
00849     return false;
00850   }
00851 
00852   if(ik_seed_state.size() != num_joints_)
00853   {
00854     ROS_ERROR_STREAM_NAMED("ikfast","Seed state must have size " << num_joints_ << " instead of size " << ik_seed_state.size());
00855     error_code.val = error_code.NO_IK_SOLUTION;
00856     return false;
00857   }
00858 
00859   if(!consistency_limits.empty() && consistency_limits.size() != num_joints_)
00860   {
00861     ROS_ERROR_STREAM_NAMED("ikfast","Consistency limits be empty or must have size " << num_joints_ << " instead of size " << consistency_limits.size());
00862     error_code.val = error_code.NO_IK_SOLUTION;
00863     return false;
00864   }
00865 
00866 
00867   // -------------------------------------------------------------------------------------------------
00868   // Initialize
00869 
00870   KDL::Frame frame;
00871   tf::poseMsgToKDL(ik_pose,frame);
00872 
00873   std::vector<double> vfree(free_params_.size());
00874 
00875   ros::Time maxTime = ros::Time::now() + ros::Duration(timeout);
00876   int counter = 0;
00877 
00878   double initial_guess = ik_seed_state[free_params_[0]];
00879   vfree[0] = initial_guess;
00880 
00881   // -------------------------------------------------------------------------------------------------
00882   // Handle consitency limits if needed
00883   int num_positive_increments;
00884   int num_negative_increments;
00885 
00886   if(!consistency_limits.empty())
00887   {
00888     // moveit replaced consistency_limit (scalar) w/ consistency_limits (vector)
00889     // Assume [0]th free_params element for now.  Probably wrong.
00890     double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess+consistency_limits[free_params_[0]]);
00891     double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess-consistency_limits[free_params_[0]]);
00892 
00893     num_positive_increments = (int)((max_limit-initial_guess)/search_discretization_);
00894     num_negative_increments = (int)((initial_guess-min_limit)/search_discretization_);
00895   }
00896   else // no consitency limits provided
00897   {
00898     num_positive_increments = (joint_max_vector_[free_params_[0]]-initial_guess)/search_discretization_;
00899     num_negative_increments = (initial_guess-joint_min_vector_[free_params_[0]])/search_discretization_;
00900   }
00901 
00902   // -------------------------------------------------------------------------------------------------
00903   // Begin searching
00904 
00905   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);
00906   if ((search_mode & OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000)
00907       ROS_WARN_STREAM_ONCE_NAMED("ikfast", "Large search space, consider increasing the search discretization");
00908   
00909   double best_costs = -1.0;
00910   std::vector<double> best_solution;
00911   int nattempts = 0, nvalid = 0;
00912 
00913   while(true)
00914   {
00915     IkSolutionList<IkReal> solutions;
00916     int numsol = solve(frame,vfree, solutions);
00917 
00918     ROS_DEBUG_STREAM_NAMED("ikfast","Found " << numsol << " solutions from IKFast");
00919 
00920     //ROS_INFO("%f",vfree[0]);
00921 
00922     if( numsol > 0 )
00923     {
00924       for(int s = 0; s < numsol; ++s)
00925       {
00926         nattempts++;
00927         std::vector<double> sol;
00928         getSolution(solutions,s,sol);
00929 
00930         bool obeys_limits = true;
00931         for(unsigned int i = 0; i < sol.size(); i++)
00932         {
00933           if(joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i]))
00934           {
00935             obeys_limits = false;
00936             break;
00937           }
00938           //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]);
00939         }
00940         if(obeys_limits)
00941         {
00942           getSolution(solutions,s,solution);
00943 
00944           // This solution is within joint limits, now check if in collision (if callback provided)
00945           if(!solution_callback.empty())
00946           {
00947             solution_callback(ik_pose, solution, error_code);
00948           }
00949           else
00950           {
00951             error_code.val = error_code.SUCCESS;
00952           }
00953 
00954           if(error_code.val == error_code.SUCCESS)
00955           {
00956             nvalid++;
00957             if (search_mode & OPTIMIZE_MAX_JOINT)
00958             {
00959               // Costs for solution: Largest joint motion
00960               double costs = 0.0;
00961               for(unsigned int i = 0; i < solution.size(); i++)
00962               {
00963                 double d = fabs(ik_seed_state[i] - solution[i]);
00964                 if (d > costs)
00965                   costs = d;
00966               }
00967               if (costs < best_costs || best_costs == -1.0)
00968               {
00969                 best_costs = costs;
00970                 best_solution = solution;
00971               }
00972             }
00973             else
00974               // Return first feasible solution
00975               return true;
00976           }
00977         }
00978       }
00979     }
00980 
00981     if(!getCount(counter, num_positive_increments, -num_negative_increments))
00982     {
00983       // Everything searched
00984       error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
00985       break;
00986     }
00987 
00988     vfree[0] = initial_guess+search_discretization_*counter;
00989     //ROS_DEBUG_STREAM_NAMED("ikfast","Attempt " << counter << " with 0th free joint having value " << vfree[0]);
00990   }
00991 
00992   ROS_DEBUG_STREAM_NAMED("ikfast", "Valid solutions: " << nvalid << "/" << nattempts);
00993 
00994   if ((search_mode & OPTIMIZE_MAX_JOINT) && best_costs != -1.0)
00995   {
00996     solution = best_solution;
00997     error_code.val = error_code.SUCCESS;
00998     return true;
00999   }
01000 
01001   // No solution found
01002   error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
01003   return false;
01004 }
01005 
01006 // Used when there are no redundant joints - aka no free params
01007 bool IKFastKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose,
01008                                            const std::vector<double> &ik_seed_state,
01009                                            std::vector<double> &solution,
01010                                            moveit_msgs::MoveItErrorCodes &error_code,
01011                                            const kinematics::KinematicsQueryOptions &options) const
01012 {
01013   ROS_DEBUG_STREAM_NAMED("ikfast","getPositionIK");
01014 
01015   if(!active_)
01016   {
01017     ROS_ERROR("kinematics not active");    
01018     return false;
01019   }
01020 
01021   std::vector<double> vfree(free_params_.size());
01022   for(std::size_t i = 0; i < free_params_.size(); ++i)
01023   {
01024     int p = free_params_[i];
01025     ROS_ERROR("%u is %f",p,ik_seed_state[p]);  // DTC
01026     vfree[i] = ik_seed_state[p];
01027   }
01028 
01029   KDL::Frame frame;
01030   tf::poseMsgToKDL(ik_pose,frame);
01031 
01032   IkSolutionList<IkReal> solutions;
01033   int numsol = solve(frame,vfree,solutions);
01034 
01035   ROS_DEBUG_STREAM_NAMED("ikfast","Found " << numsol << " solutions from IKFast");
01036 
01037   if(numsol)
01038   {
01039     for(int s = 0; s < numsol; ++s)
01040     {
01041       std::vector<double> sol;
01042       getSolution(solutions,s,sol);
01043       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]);
01044 
01045       bool obeys_limits = true;
01046       for(unsigned int i = 0; i < sol.size(); i++)
01047       {
01048         // Add tolerance to limit check
01049         if(joint_has_limits_vector_[i] && ( (sol[i] < (joint_min_vector_[i]-LIMIT_TOLERANCE)) ||
01050                                             (sol[i] > (joint_max_vector_[i]+LIMIT_TOLERANCE)) ) )
01051         {
01052           // One element of solution is not within limits
01053           obeys_limits = false;
01054           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]);
01055           break;
01056         }
01057       }
01058       if(obeys_limits)
01059       {
01060         // All elements of solution obey limits
01061         getSolution(solutions,s,solution);
01062         error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
01063         return true;
01064       }
01065     }
01066   }
01067   else
01068   {
01069     ROS_DEBUG_STREAM_NAMED("ikfast","No IK solution");
01070   }
01071 
01072   error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
01073   return false;
01074 }
01075 
01076 bool IKFastKinematicsPlugin::getPositionIK(const std::vector<geometry_msgs::Pose> &ik_poses,
01077                                            const std::vector<double> &ik_seed_state,
01078                                            std::vector< std::vector<double> >& solutions,
01079                                            kinematics::KinematicsResult& result,
01080                                            const kinematics::KinematicsQueryOptions &options) const
01081 {
01082   ROS_DEBUG_STREAM_NAMED("ikfast","getPositionIK with multiple solutions");
01083 
01084   if(!active_)
01085   {
01086     ROS_ERROR("kinematics not active");
01087     result.kinematic_error = kinematics::KinematicErrors::SOLVER_NOT_ACTIVE;
01088     return false;
01089   }
01090 
01091   if(ik_poses.empty())
01092   {
01093     ROS_ERROR("ik_poses is empty");
01094     result.kinematic_error = kinematics::KinematicErrors::EMPTY_TIP_POSES;
01095     return false;
01096   }
01097 
01098   if(ik_poses.size() > 1)
01099   {
01100     ROS_ERROR("ik_poses contains multiple entries, only one is allowed");
01101     result.kinematic_error = kinematics::KinematicErrors::MULTIPLE_TIPS_NOT_SUPPORTED;
01102     return false;
01103   }
01104 
01105   if(ik_seed_state.size() < num_joints_)
01106   {
01107     ROS_ERROR_STREAM("ik_seed_state only has "<<ik_seed_state.size()<<" entries, this ikfast solver requires "<<num_joints_);
01108     return false;
01109   }
01110 
01111   KDL::Frame frame;
01112   tf::poseMsgToKDL(ik_poses[0],frame);
01113 
01114   // solving ik
01115   std::vector< IkSolutionList<IkReal> > solution_set;
01116   IkSolutionList<IkReal> ik_solutions;
01117   std::vector<double> vfree;
01118   int numsol = 0;
01119   std::vector<double> sampled_joint_vals;
01120   if(!redundant_joint_indices_.empty())
01121   {
01122     // initializing from seed
01123     sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]);
01124 
01125     // checking joint limits when using no discretization
01126     if(options.discretization_method == kinematics::DiscretizationMethods::NO_DISCRETIZATION &&
01127         joint_has_limits_vector_[redundant_joint_indices_.front()])
01128     {
01129       double joint_min = joint_min_vector_[redundant_joint_indices_.front()];
01130       double joint_max = joint_max_vector_[redundant_joint_indices_.front()];
01131 
01132       double jv = sampled_joint_vals[0];
01133       if(!( (jv > (joint_min - LIMIT_TOLERANCE)) && (jv < (joint_max + LIMIT_TOLERANCE)) ))
01134       {
01135         result.kinematic_error = kinematics::KinematicErrors::IK_SEED_OUTSIDE_LIMITS;
01136         ROS_ERROR_STREAM("ik seed is out of bounds");
01137         return false;
01138       }
01139 
01140     }
01141 
01142 
01143     // computing all solutions sets for each sampled value of the redundant joint
01144     if(!sampleRedundantJoint(options.discretization_method,sampled_joint_vals))
01145     {
01146       result.kinematic_error = kinematics::KinematicErrors::UNSUPORTED_DISCRETIZATION_REQUESTED;
01147       return false;
01148     }
01149 
01150     for(unsigned int i = 0; i < sampled_joint_vals.size(); i++)
01151     {
01152       vfree.clear();
01153       vfree.push_back(sampled_joint_vals[i]);
01154       numsol += solve(frame,vfree,ik_solutions);
01155       solution_set.push_back(ik_solutions);
01156     }
01157   }
01158   else
01159   {
01160     // computing for single solution set
01161     numsol = solve(frame,vfree,ik_solutions);
01162     solution_set.push_back(ik_solutions);
01163   }
01164 
01165   ROS_DEBUG_STREAM_NAMED("ikfast","Found " << numsol << " solutions from IKFast");
01166   bool solutions_found = false;
01167   if( numsol > 0 )
01168   {
01169     /*
01170       Iterating through all solution sets and storing those that do not exceed joint limits.
01171     */
01172     for(unsigned int r = 0; r < solution_set.size() ; r++)
01173     {
01174 
01175       ik_solutions = solution_set[r];
01176       numsol = ik_solutions.GetNumSolutions();
01177       for(int s = 0; s < numsol; ++s)
01178       {
01179         std::vector<double> sol;
01180         getSolution(ik_solutions,s,sol);
01181 
01182         bool obeys_limits = true;
01183         for(unsigned int i = 0; i < sol.size(); i++)
01184         {
01185           // Add tolerance to limit check
01186           if(joint_has_limits_vector_[i] && ( (sol[i] < (joint_min_vector_[i]-LIMIT_TOLERANCE)) ||
01187                                               (sol[i] > (joint_max_vector_[i]+LIMIT_TOLERANCE)) ) )
01188           {
01189             // One element of solution is not within limits
01190             obeys_limits = false;
01191             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]);
01192             break;
01193           }
01194         }
01195         if(obeys_limits)
01196         {
01197           // All elements of solution obey limits
01198           solutions_found = true;
01199           solutions.push_back(sol);
01200         }
01201       }
01202     }
01203 
01204     if(solutions_found)
01205     {
01206       result.kinematic_error = kinematics::KinematicErrors::OK;
01207       return true;
01208     }
01209   }
01210   else
01211   {
01212     ROS_DEBUG_STREAM_NAMED("ikfast","No IK solution");
01213   }
01214 
01215   result.kinematic_error = kinematics::KinematicErrors::NO_SOLUTION;
01216   return false;
01217 }
01218 
01219 bool IKFastKinematicsPlugin::sampleRedundantJoint(kinematics::DiscretizationMethod method, std::vector<double>& sampled_joint_vals) const
01220 {
01221   double joint_min = -M_PI;
01222   double joint_max = M_PI;
01223   int index =  redundant_joint_indices_.front();
01224   double joint_dscrt = redundant_joint_discretization_.at(index);
01225 
01226   if(joint_has_limits_vector_[redundant_joint_indices_.front()])
01227   {
01228     joint_min = joint_min_vector_[index];
01229     joint_max = joint_max_vector_[index];
01230   }
01231 
01232 
01233   switch(method)
01234   {
01235     case kinematics::DiscretizationMethods::ALL_DISCRETIZED:
01236     {
01237       int steps = std::ceil((joint_max - joint_min)/joint_dscrt);
01238       for(unsigned int i = 0; i < steps;i++)
01239       {
01240         sampled_joint_vals.push_back(joint_min + joint_dscrt*i);
01241       }
01242       sampled_joint_vals.push_back(joint_max);
01243     }
01244       break;
01245     case kinematics::DiscretizationMethods::ALL_RANDOM_SAMPLED:
01246     {
01247       int steps = std::ceil((joint_max - joint_min)/joint_dscrt);
01248       steps = steps > 0 ? steps : 1;
01249       double diff = joint_max - joint_min;
01250       for(int i = 0; i < steps; i++)
01251       {
01252         sampled_joint_vals.push_back( ((diff*std::rand())/(static_cast<double>(RAND_MAX))) + joint_min );
01253       }
01254     }
01255 
01256       break;
01257     case kinematics::DiscretizationMethods::NO_DISCRETIZATION:
01258 
01259       break;
01260     default:
01261       ROS_ERROR_STREAM("Discretization method "<<method<<" is not supported");
01262       return false;
01263   }
01264 
01265   return true;
01266 }
01267 
01268 
01269 } // end namespace
01270 
01271 //register IKFastKinematicsPlugin as a KinematicsBase implementation
01272 #include <pluginlib/class_list_macros.h>
01273 PLUGINLIB_EXPORT_CLASS(ikfast_kinematics_plugin::IKFastKinematicsPlugin, kinematics::KinematicsBase);


fetch_ikfast_plugin
Author(s): Michael Ferguson
autogenerated on Sat Apr 27 2019 03:12:11