pr2_arm_ik_solver.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, 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 */
00036 
00037 #include <moveit/pr2_arm_kinematics/pr2_arm_ik_solver.h>
00038 
00039 using namespace Eigen;
00040 using namespace pr2_arm_kinematics;
00041 
00042 PR2ArmIKSolver::PR2ArmIKSolver(const urdf::Model &robot_model,
00043                                const std::string &root_frame_name,
00044                                const std::string &tip_frame_name,
00045                                const double &search_discretization_angle,
00046                                const int &free_angle):ChainIkSolverPos()
00047 {
00048   pr2_arm_ik_ = new PR2ArmIK();
00049   search_discretization_angle_ = search_discretization_angle;
00050   free_angle_ = free_angle;
00051   root_frame_name_ = root_frame_name;
00052   if(!pr2_arm_ik_->init(robot_model, root_frame_name, tip_frame_name))
00053     active_ = false;
00054   else
00055     active_ = true;
00056 }
00057 
00058 void PR2ArmIKSolver::getSolverInfo(moveit_msgs::KinematicSolverInfo &response)
00059 {
00060   pr2_arm_ik_->getSolverInfo(response);
00061 }
00062 
00063 int PR2ArmIKSolver::CartToJnt(const KDL::JntArray& q_init,
00064                               const KDL::Frame& p_in,
00065                               KDL::JntArray &q_out)
00066 {
00067   Eigen::Matrix4f b = KDLToEigenMatrix(p_in);
00068   std::vector<std::vector<double> > solution_ik;
00069   if(free_angle_ == 0)
00070   {
00071     ROS_DEBUG("Solving with free angle: %d", free_angle_);
00072     pr2_arm_ik_->computeIKShoulderPan(b, q_init(0), solution_ik);
00073   }
00074   else
00075   {
00076     pr2_arm_ik_->computeIKShoulderRoll(b, q_init(2), solution_ik);
00077   }
00078 
00079   if(solution_ik.empty())
00080     return -1;
00081 
00082   double min_distance = 1e6;
00083   int min_index = -1;
00084 
00085   for(int i=0; i< (int) solution_ik.size(); ++i)
00086   {
00087     ROS_DEBUG("Solution : %d", (int)solution_ik.size());
00088     for(int j=0; j < (int)solution_ik[i].size(); j++)
00089     {
00090       ROS_DEBUG("Joint %d: %f", j, solution_ik[i][j]);
00091     }
00092 
00093     double tmp_distance = computeEuclideanDistance(solution_ik[i], q_init);
00094     if(tmp_distance < min_distance)
00095     {
00096       min_distance = tmp_distance;
00097       min_index = i;
00098     }
00099   }
00100 
00101   if(min_index > -1)
00102   {
00103     q_out.resize((int)solution_ik[min_index].size());
00104     for(int i=0; i < (int)solution_ik[min_index].size(); ++i)
00105     {
00106       q_out(i) = solution_ik[min_index][i];
00107     }
00108     return 1;
00109   }
00110   else
00111     return -1;
00112 }
00113 
00114 int PR2ArmIKSolver::CartToJnt(const KDL::JntArray& q_init,
00115                               const KDL::Frame& p_in,
00116                               std::vector<KDL::JntArray> &q_out)
00117 {
00118   Eigen::Matrix4f b = KDLToEigenMatrix(p_in);
00119   std::vector<std::vector<double> > solution_ik;
00120   KDL::JntArray q;
00121 
00122   if(free_angle_ == 0)
00123   {
00124     pr2_arm_ik_->computeIKShoulderPan(b, q_init(0), solution_ik);
00125   }
00126   else
00127   {
00128     pr2_arm_ik_->computeIKShoulderRoll(b, q_init(2), solution_ik);
00129   }
00130 
00131   if(solution_ik.empty())
00132     return -1;
00133 
00134   q.resize(7);
00135   q_out.clear();
00136   for(int i=0; i< (int) solution_ik.size(); ++i)
00137   {
00138     for(int j=0; j < 7; j++)
00139     {
00140       q(j) = solution_ik[i][j];
00141     }
00142     q_out.push_back(q);
00143   }
00144   return 1;
00145 }
00146 
00147 bool PR2ArmIKSolver::getCount(int &count,
00148                               const int &max_count,
00149                               const int &min_count)
00150 {
00151   if(count > 0)
00152   {
00153     if(-count >= min_count)
00154     {
00155       count = -count;
00156       return true;
00157     }
00158     else if(count+1 <= max_count)
00159     {
00160       count = count+1;
00161       return true;
00162     }
00163     else
00164     {
00165       return false;
00166     }
00167   }
00168   else
00169   {
00170     if(1-count <= max_count)
00171     {
00172       count = 1-count;
00173       return true;
00174     }
00175     else if(count-1 >= min_count)
00176     {
00177       count = count -1;
00178       return true;
00179     }
00180     else
00181       return false;
00182   }
00183 }
00184 
00185 int PR2ArmIKSolver::CartToJntSearch(const KDL::JntArray& q_in,
00186                                     const KDL::Frame& p_in,
00187                                     std::vector<KDL::JntArray> &q_out,
00188                                     const double &timeout)
00189 {
00190   KDL::JntArray q_init = q_in;
00191   double initial_guess = q_init(free_angle_);
00192 
00193   ros::WallTime start_time = ros::WallTime::now();
00194   double loop_time = 0;
00195   int count = 0;
00196 
00197   int num_positive_increments = (int)((pr2_arm_ik_->solver_info_.limits[free_angle_].max_position-initial_guess)/search_discretization_angle_);
00198   int num_negative_increments = (int)((initial_guess-pr2_arm_ik_->solver_info_.limits[free_angle_].min_position)/search_discretization_angle_);
00199   ROS_DEBUG("positive increments, negative increments: %d %d", num_positive_increments, num_negative_increments);
00200   while(loop_time < timeout)
00201   {
00202     if(CartToJnt(q_init, p_in, q_out) > 0)
00203       return 1;
00204     if(!getCount(count, num_positive_increments, -num_negative_increments))
00205       return -1;
00206     q_init(free_angle_) = initial_guess + search_discretization_angle_ * count;
00207     ROS_DEBUG("%d, %f",count, q_init(free_angle_));
00208     loop_time = (ros::WallTime::now()-start_time).toSec();
00209   }
00210   if(loop_time >= timeout)
00211   {
00212     ROS_DEBUG("IK Timed out in %f seconds", timeout);
00213     return TIMED_OUT;
00214   }
00215   else
00216   {
00217     ROS_DEBUG("No IK solution was found");
00218     return NO_IK_SOLUTION;
00219   }
00220   return NO_IK_SOLUTION;
00221 }
00222 
00223 int PR2ArmIKSolver::CartToJntSearch(const KDL::JntArray& q_in,
00224                                     const KDL::Frame& p_in,
00225                                     KDL::JntArray &q_out,
00226                                     const double &timeout,
00227                                     const double& consistency_limit)
00228 {
00229   moveit_msgs::MoveItErrorCodes error_code;
00230   static kinematics::KinematicsBase::IKCallbackFn solution_callback = 0;
00231   return CartToJntSearch(q_in, p_in, q_out, timeout, true, consistency_limit, error_code, solution_callback);
00232 }
00233 
00234 int PR2ArmIKSolver:: CartToJntSearch(const KDL::JntArray& q_in,
00235                                      const KDL::Frame& p_in,
00236                                      KDL::JntArray &q_out,
00237                                      const double &timeout,
00238                                      moveit_msgs::MoveItErrorCodes &error_code,
00239                                      const kinematics::KinematicsBase::IKCallbackFn &solution_callback)
00240 {
00241   return CartToJntSearch(q_in, p_in, q_out, timeout, false, 0.0, error_code, solution_callback);
00242 }
00243 
00244 
00245 int PR2ArmIKSolver::CartToJntSearch(const KDL::JntArray& q_in,
00246                                     const KDL::Frame& p_in,
00247                                     KDL::JntArray &q_out,
00248                                     const double &timeout,
00249                                     const double& consistency_limit,
00250                                     moveit_msgs::MoveItErrorCodes &error_code,
00251                                     const kinematics::KinematicsBase::IKCallbackFn &solution_callback)
00252 {
00253   return CartToJntSearch(q_in, p_in, q_out, timeout, true, consistency_limit, error_code, solution_callback);
00254 }
00255 
00256 int PR2ArmIKSolver::CartToJntSearch(const KDL::JntArray& q_in,
00257                                     const KDL::Frame& p_in,
00258                                     KDL::JntArray &q_out,
00259                                     const double &timeout,
00260                                     bool use_consistency_limit,
00261                                     const double &max_consistency,
00262                                     moveit_msgs::MoveItErrorCodes &error_code,
00263                                     const kinematics::KinematicsBase::IKCallbackFn &solution_callback)
00264 {
00265   KDL::JntArray q_init = q_in;
00266   double initial_guess = q_init(free_angle_);
00267 
00268   ros::WallTime start_time = ros::WallTime::now();
00269   double loop_time = 0;
00270   int count = 0;
00271 
00272   double max_limit, min_limit;
00273   if(use_consistency_limit)
00274   {
00275     max_limit = fmin(pr2_arm_ik_->solver_info_.limits[free_angle_].max_position, initial_guess+max_consistency);
00276     min_limit = fmax(pr2_arm_ik_->solver_info_.limits[free_angle_].min_position, initial_guess-max_consistency);
00277   }
00278   else
00279   {
00280     max_limit = pr2_arm_ik_->solver_info_.limits[free_angle_].max_position;
00281     min_limit = pr2_arm_ik_->solver_info_.limits[free_angle_].min_position;
00282   }
00283 
00284   int num_positive_increments = (int)((max_limit-initial_guess)/search_discretization_angle_);
00285   int num_negative_increments = (int)((initial_guess-min_limit)/search_discretization_angle_);
00286 
00287   if(use_consistency_limit)
00288   {
00289     ROS_DEBUG("Consistency[Joint: %d]: Initial guess %f, consistency %f", free_angle_, initial_guess, max_consistency);
00290     ROS_DEBUG("Max limit %f = max(%f, %f)", max_limit, pr2_arm_ik_->solver_info_.limits[free_angle_].max_position, initial_guess+max_consistency);
00291     ROS_DEBUG("Min limit %f = min(%f, %f)", min_limit, pr2_arm_ik_->solver_info_.limits[free_angle_].min_position, initial_guess-max_consistency);
00292   }
00293   else
00294   {
00295     ROS_DEBUG("Consistency[Joint: %d]: Initial guess %f", free_angle_, initial_guess);
00296     ROS_DEBUG("Max limit %f", max_limit);
00297     ROS_DEBUG("Min limit %f", min_limit);
00298   }
00299 
00300   ROS_DEBUG("positive increments, negative increments: %d %d", num_positive_increments, num_negative_increments);
00301 
00302   unsigned int testnum = 0;
00303   geometry_msgs::Pose ik_pose_msg;
00304   tf::poseKDLToMsg(p_in, ik_pose_msg);
00305 
00306   ros::WallTime s = ros::WallTime::now();
00307 
00308   while(loop_time < timeout)
00309   {
00310     testnum++;
00311     if(CartToJnt(q_init, p_in, q_out) > 0)
00312     {
00313       if(solution_callback)
00314       {
00315         std::vector<double> ik_solution(7,0.0);
00316         for(int i=0; i < 7; ++i)
00317           ik_solution[i] = q_out(i);
00318 
00319         solution_callback(ik_pose_msg, ik_solution, error_code);
00320         if(error_code.val == error_code.SUCCESS)
00321         {
00322           ROS_DEBUG("Difference is %f %f", q_in(free_angle_), q_out(free_angle_));
00323           ROS_DEBUG("Success with %d in %f", testnum, (ros::WallTime::now()-s).toSec());
00324           return 1;
00325         }
00326       }
00327       else
00328       {
00329         error_code.val = error_code.SUCCESS;
00330         return 1;
00331       }
00332     }
00333     if(!getCount(count, num_positive_increments, -num_negative_increments))
00334     {
00335       ROS_DEBUG("Failure with %d in %f", testnum, (ros::WallTime::now()-s).toSec());
00336       error_code.val = error_code.NO_IK_SOLUTION;
00337       return -1;
00338     }
00339     q_init(free_angle_) = initial_guess + search_discretization_angle_ * count;
00340     ROS_DEBUG("Redundancy search, index:%d, free angle value: %f", count, q_init(free_angle_));
00341     loop_time = (ros::WallTime::now()-start_time).toSec();
00342   }
00343   if(loop_time >= timeout)
00344   {
00345     ROS_DEBUG("IK Timed out in %f seconds",timeout);
00346     error_code.val = error_code.TIMED_OUT;
00347   }
00348   else
00349   {
00350     error_code.val = error_code.NO_IK_SOLUTION;
00351   }
00352   return -1;
00353 }
00354 
00355 
00356 std::string PR2ArmIKSolver::getFrameId()
00357 {
00358   return root_frame_name_;
00359 }


pr2_moveit_plugins
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Sep 14 2015 14:17:49