pr2_arm_kinematics_plugin.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2008, Willow Garage, Inc.
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
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of Willow Garage, Inc. nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Sachin Chitta
00036 *********************************************************************/
00037 
00038 #include <moveit/pr2_arm_kinematics/pr2_arm_kinematics_plugin.h>
00039 #include <geometry_msgs/PoseStamped.h>
00040 #include <kdl_parser/kdl_parser.hpp>
00041 #include <tf_conversions/tf_kdl.h>
00042 #include <ros/ros.h>
00043 #include <algorithm>
00044 #include <numeric>
00045 
00046 #include <pluginlib/class_list_macros.h>
00047 
00048 using namespace KDL;
00049 using namespace tf;
00050 using namespace std;
00051 using namespace ros;
00052 
00053 //register PR2ArmKinematics as a KinematicsBase implementation
00054 PLUGINLIB_EXPORT_CLASS(pr2_arm_kinematics::PR2ArmKinematicsPlugin, kinematics::KinematicsBase);
00055 
00056 namespace pr2_arm_kinematics {
00057 
00058 PR2ArmKinematicsPlugin::PR2ArmKinematicsPlugin():active_(false){}
00059 
00060 bool PR2ArmKinematicsPlugin::isActive()
00061 {
00062   if(active_)
00063     return true;
00064   return false;
00065 }
00066 
00067 bool PR2ArmKinematicsPlugin::initialize(const std::string& robot_description,
00068                                         const std::string& group_name,
00069                                         const std::string& base_name,
00070                                         const std::string& tip_name,
00071                                         double search_discretization)
00072 {
00073   setValues(robot_description, group_name, base_name, tip_name,search_discretization);
00074   urdf::Model robot_model;
00075   std::string xml_string;
00076   ros::NodeHandle private_handle("~/"+group_name);
00077   dimension_ = 7;
00078   while(!loadRobotModel(private_handle,robot_model,xml_string) && private_handle.ok())
00079   {
00080     ROS_ERROR("Could not load robot model. Are you sure the robot model is on the parameter server?");
00081     ros::Duration(0.5).sleep();
00082   }
00083 
00084   ROS_DEBUG("Loading KDL Tree");
00085   if(!getKDLChain(xml_string,base_frame_,tip_frame_,kdl_chain_))
00086   {
00087     active_ = false;
00088     ROS_ERROR("Could not load kdl tree");
00089   }
00090   ROS_DEBUG("Advertising services");
00091   jnt_to_pose_solver_.reset(new KDL::ChainFkSolverPos_recursive(kdl_chain_));
00092   private_handle.param<int>("free_angle",free_angle_,2);
00093 
00094   pr2_arm_ik_solver_.reset(new pr2_arm_kinematics::PR2ArmIKSolver(robot_model, base_frame_,tip_frame_, search_discretization_,free_angle_));
00095   if(!pr2_arm_ik_solver_->active_)
00096   {
00097     ROS_ERROR("Could not load ik");
00098     active_ = false;
00099   }
00100   else
00101   {
00102 
00103     pr2_arm_ik_solver_->getSolverInfo(ik_solver_info_);
00104     pr2_arm_kinematics::getKDLChainInfo(kdl_chain_,fk_solver_info_);
00105     fk_solver_info_.joint_names = ik_solver_info_.joint_names;
00106 
00107     for(unsigned int i=0; i < ik_solver_info_.joint_names.size(); i++)
00108     {
00109       ROS_DEBUG("PR2Kinematics:: joint name: %s",ik_solver_info_.joint_names[i].c_str());
00110     }
00111     for(unsigned int i=0; i < ik_solver_info_.link_names.size(); i++)
00112     {
00113       ROS_DEBUG("PR2Kinematics can solve IK for %s",ik_solver_info_.link_names[i].c_str());
00114     }
00115     for(unsigned int i=0; i < fk_solver_info_.link_names.size(); i++)
00116     {
00117       ROS_DEBUG("PR2Kinematics can solve FK for %s",fk_solver_info_.link_names[i].c_str());
00118     }
00119     ROS_DEBUG("PR2KinematicsPlugin::active for %s",group_name.c_str());
00120     active_ = true;
00121   }
00122   pr2_arm_ik_solver_->setFreeAngle(2);
00123   return active_;
00124 }
00125 
00126 bool PR2ArmKinematicsPlugin::getPositionIK(const geometry_msgs::Pose &ik_pose,
00127                                            const std::vector<double> &ik_seed_state,
00128                                            std::vector<double> &solution,
00129                                            moveit_msgs::MoveItErrorCodes &error_code,
00130                                            const kinematics::KinematicsQueryOptions &options) const
00131 {
00132   if(!active_)
00133   {
00134     ROS_ERROR("kinematics not active");
00135     error_code.val = error_code.NO_IK_SOLUTION;
00136     return false;
00137   }
00138 
00139   KDL::Frame pose_desired;
00140   tf::poseMsgToKDL(ik_pose, pose_desired);
00141 
00142   //Do the IK
00143   KDL::JntArray jnt_pos_in;
00144   KDL::JntArray jnt_pos_out;
00145   jnt_pos_in.resize(dimension_);
00146   for(int i=0; i < dimension_; i++)
00147   {
00148     jnt_pos_in(i) = ik_seed_state[i];
00149   }
00150 
00151   int ik_valid = pr2_arm_ik_solver_->CartToJnt(jnt_pos_in,
00152                                                pose_desired,
00153                                                jnt_pos_out);
00154   if(ik_valid == pr2_arm_kinematics::NO_IK_SOLUTION)
00155   {
00156     error_code.val = error_code.NO_IK_SOLUTION;
00157     return false;
00158   }
00159 
00160   if(ik_valid >= 0)
00161   {
00162     solution.resize(dimension_);
00163     for(int i=0; i < dimension_; i++)
00164     {
00165       solution[i] = jnt_pos_out(i);
00166     }
00167     error_code.val = error_code.SUCCESS;
00168     return true;
00169   }
00170   else
00171   {
00172     ROS_DEBUG("An IK solution could not be found");
00173     error_code.val = error_code.NO_IK_SOLUTION;
00174     return false;
00175   }
00176 }
00177 
00178 bool PR2ArmKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00179                                               const std::vector<double> &ik_seed_state,
00180                                               double timeout,
00181                                               std::vector<double> &solution,
00182                                               moveit_msgs::MoveItErrorCodes &error_code,
00183                                               const kinematics::KinematicsQueryOptions &options) const
00184 {
00185   static IKCallbackFn solution_callback = 0;
00186   static std::vector<double> consistency_limits;
00187   return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code);
00188 }
00189 
00190 bool PR2ArmKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00191                                               const std::vector<double> &ik_seed_state,
00192                                               double timeout,
00193                                               const std::vector<double> &consistency_limits,
00194                                               std::vector<double> &solution,
00195                                               moveit_msgs::MoveItErrorCodes &error_code,
00196                                               const kinematics::KinematicsQueryOptions &options) const
00197 {
00198   static IKCallbackFn solution_callback = 0;
00199   return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code);
00200 }
00201 
00202 bool PR2ArmKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00203                                               const std::vector<double> &ik_seed_state,
00204                                               double timeout,
00205                                               std::vector<double> &solution,
00206                                               const IKCallbackFn &solution_callback,
00207                                               moveit_msgs::MoveItErrorCodes &error_code,
00208                                               const kinematics::KinematicsQueryOptions &options) const
00209 {
00210   static std::vector<double> consistency_limits;
00211   return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code);
00212 }
00213 
00214 bool PR2ArmKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
00215                                               const std::vector<double> &ik_seed_state,
00216                                               double timeout,
00217                                               const std::vector<double> &consistency_limits,
00218                                               std::vector<double> &solution,
00219                                               const IKCallbackFn &solution_callback,
00220                                               moveit_msgs::MoveItErrorCodes &error_code,
00221                                               const kinematics::KinematicsQueryOptions &options) const
00222 {
00223   if(!active_)
00224   {
00225     ROS_ERROR("kinematics not active");
00226     error_code.val = error_code.FAILURE;
00227     return false;
00228   }
00229   if(!consistency_limits.empty() && consistency_limits.size() != dimension_)
00230   {
00231     ROS_ERROR("Consistency limits should be of size: %d",dimension_);
00232     error_code.val = error_code.FAILURE;
00233     return false;
00234   }
00235 
00236   KDL::Frame pose_desired;
00237   tf::poseMsgToKDL(ik_pose, pose_desired);
00238 
00239   //Do the IK
00240   KDL::JntArray jnt_pos_in;
00241   KDL::JntArray jnt_pos_out;
00242   jnt_pos_in.resize(dimension_);
00243   for(int i=0; i < dimension_; i++)
00244   {
00245     jnt_pos_in(i) = ik_seed_state[i];
00246   }
00247 
00248   int ik_valid;
00249   if(consistency_limits.empty())
00250   {
00251     ik_valid = pr2_arm_ik_solver_->CartToJntSearch(jnt_pos_in,
00252                                                    pose_desired,
00253                                                    jnt_pos_out,
00254                                                    timeout,
00255                                                    error_code,
00256                                                    solution_callback ?
00257                                                    boost::bind(solution_callback, _1, _2, _3):
00258                                                    IKCallbackFn());
00259   }
00260   else
00261   {
00262     ik_valid = pr2_arm_ik_solver_->CartToJntSearch(jnt_pos_in,
00263                                                    pose_desired,
00264                                                    jnt_pos_out,
00265                                                    timeout,
00266                                                    consistency_limits[free_angle_],
00267                                                    error_code,
00268                                                    solution_callback ?
00269                                                    boost::bind(solution_callback, _1, _2, _3):
00270                                                    IKCallbackFn());
00271   }
00272 
00273   if(ik_valid == pr2_arm_kinematics::NO_IK_SOLUTION)
00274     return false;
00275 
00276   if(ik_valid >= 0)
00277   {
00278     solution.resize(dimension_);
00279     for(int i=0; i < dimension_; i++)
00280     {
00281       solution[i] = jnt_pos_out(i);
00282     }
00283     return true;
00284   }
00285   else
00286   {
00287     ROS_DEBUG("An IK solution could not be found");
00288     return false;
00289   }
00290 }
00291 
00292 bool PR2ArmKinematicsPlugin::getPositionFK(const std::vector<std::string> &link_names,
00293                                            const std::vector<double> &joint_angles,
00294                                            std::vector<geometry_msgs::Pose> &poses) const
00295 {
00296   if(!active_)
00297   {
00298     ROS_ERROR("kinematics not active");
00299     return false;
00300   }
00301 
00302   KDL::Frame p_out;
00303   KDL::JntArray jnt_pos_in;
00304   geometry_msgs::PoseStamped pose;
00305   tf::Stamped<tf::Pose> tf_pose;
00306 
00307   jnt_pos_in.resize(dimension_);
00308   for(int i=0; i < dimension_; i++)
00309   {
00310     jnt_pos_in(i) = joint_angles[i];
00311     //    ROS_DEBUG("Joint angle: %d %f",i,joint_angles[i]);
00312   }
00313 
00314   poses.resize(link_names.size());
00315 
00316   bool valid = true;
00317   for(unsigned int i=0; i < poses.size(); i++)
00318   {
00319     //    ROS_DEBUG("End effector index: %d",pr2_arm_kinematics::getKDLSegmentIndex(kdl_chain_,link_names[i]));
00320     if(jnt_to_pose_solver_->JntToCart(jnt_pos_in,p_out,pr2_arm_kinematics::getKDLSegmentIndex(kdl_chain_,link_names[i])) >= 0)
00321     {
00322       tf::poseKDLToMsg(p_out,poses[i]);
00323     }
00324     else
00325     {
00326       ROS_ERROR("Could not compute FK for %s",link_names[i].c_str());
00327       valid = false;
00328     }
00329   }
00330   return valid;
00331 }
00332 
00333 const std::vector<std::string>& PR2ArmKinematicsPlugin::getJointNames() const
00334 {
00335   if(!active_)
00336   {
00337     ROS_ERROR("kinematics not active");
00338   }
00339   return ik_solver_info_.joint_names;
00340 }
00341 
00342 const std::vector<std::string>& PR2ArmKinematicsPlugin::getLinkNames() const
00343 {
00344   if(!active_)
00345   {
00346     ROS_ERROR("kinematics not active");
00347   }
00348   return fk_solver_info_.link_names;
00349 }
00350 
00351 } // namespace


pr2_moveit_plugins
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 11:14:04