pr2_arm_kinematics_plugin.h
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 the Willow Garage 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 #ifndef PR2_ARM_IK_NODE_H
00039 #define PR2_ARM_IK_NODE_H
00040 
00041 #include <ros/ros.h>
00042 #include <tf/tf.h>
00043 #include <tf/transform_listener.h>
00044 
00045 #include <angles/angles.h>
00046 #include <pr2_arm_kinematics/pr2_arm_ik_solver.h>
00047 #include <tf_conversions/tf_kdl.h>
00048 
00049 #include <kinematics_msgs/GetPositionFK.h>
00050 #include <kinematics_msgs/GetPositionIK.h>
00051 #include <kinematics_msgs/GetKinematicSolverInfo.h>
00052 #include <arm_navigation_msgs/ArmNavigationErrorCodes.h>
00053 
00054 #include <kdl/chainfksolverpos_recursive.hpp>
00055 
00056 #include <boost/shared_ptr.hpp>
00057 
00058 #include <kinematics_base/kinematics_base.h>
00059 
00060 namespace pr2_arm_kinematics
00061 {
00062 class PR2ArmKinematicsPlugin : public kinematics::KinematicsBase
00063 {
00064 public:
00065 
00069   PR2ArmKinematicsPlugin();
00070 
00075   bool isActive();
00076 
00084   virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00085                              const std::vector<double> &ik_seed_state,
00086                              std::vector<double> &solution,
00087                              int &error_code);      
00096   virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00097                                 const std::vector<double> &ik_seed_state,
00098                                 const double &timeout,
00099                                 std::vector<double> &solution,
00100                                 int &error_code);      
00110   virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00111                                 const std::vector<double> &ik_seed_state,
00112                                 const double &timeout,
00113                                 const unsigned int& redundancy,         
00114                                 const double &consistency_limit,
00115                                 std::vector<double> &solution,
00116                                 int &error_code);      
00117 
00126   virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00127                                 const std::vector<double> &ik_seed_state,
00128                                 const double &timeout,
00129                                 std::vector<double> &solution,
00130                                 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &desired_pose_callback,
00131                                 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &solution_callback,
00132                                 int &error_code);      
00133 
00144   virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00145                                 const std::vector<double> &ik_seed_state,
00146                                 const double &timeout,
00147                                 const unsigned int& redundancy,
00148                                 const double &consistency_limit,
00149                                 std::vector<double> &solution,
00150                                 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &desired_pose_callback,
00151                                 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &solution_callback,
00152                                 int &error_code);      
00153     
00160   virtual bool getPositionFK(const std::vector<std::string> &link_names,
00161                              const std::vector<double> &joint_angles, 
00162                              std::vector<geometry_msgs::Pose> &poses);
00163     
00168   virtual bool initialize(const std::string& group_name,
00169                           const std::string& base_name,
00170                           const std::string& tip_name,
00171                           const double& search_discretization);
00172     
00176   const std::vector<std::string>& getJointNames() const;
00177     
00181   const std::vector<std::string>& getLinkNames() const;
00182     
00183 protected:
00184 
00185   bool active_;
00186   int free_angle_;
00187   urdf::Model robot_model_;
00188   ros::NodeHandle node_handle_, root_handle_;
00189   boost::shared_ptr<pr2_arm_kinematics::PR2ArmIKSolver> pr2_arm_ik_solver_;
00190   ros::ServiceServer ik_service_,fk_service_,ik_solver_info_service_,fk_solver_info_service_;
00191   //tf::TransformListener tf_;
00192   std::string root_name_;
00193   int dimension_;
00194   boost::shared_ptr<KDL::ChainFkSolverPos_recursive> jnt_to_pose_solver_;
00195   KDL::Chain kdl_chain_;
00196   kinematics_msgs::KinematicSolverInfo ik_solver_info_, fk_solver_info_;
00197 
00198   boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> desiredPoseCallback_;
00199   boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> solutionCallback_;    
00200   void desiredPoseCallback(const KDL::JntArray& jnt_array, 
00201                            const KDL::Frame& ik_pose,
00202                            arm_navigation_msgs::ArmNavigationErrorCodes& error_code);
00203 
00204   void jointSolutionCallback(const KDL::JntArray& jnt_array, 
00205                              const KDL::Frame& ik_pose,
00206                              arm_navigation_msgs::ArmNavigationErrorCodes& error_code);
00207 
00208 
00209 };
00210 }
00211 
00212 #endif


pr2_arm_kinematics
Author(s): Sachin Chitta
autogenerated on Thu Jan 2 2014 11:40:43