Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #ifndef PR2_ARM_IK_NODE_H
00038 #define PR2_ARM_IK_NODE_H
00039 
00040 #include <ros/ros.h>
00041 #include <tf/tf.h>
00042 #include <tf/transform_listener.h>
00043 
00044 #include <angles/angles.h>
00045 #include <pr2_arm_kinematics/pr2_arm_ik_solver.h>
00046 #include <tf_conversions/tf_kdl.h>
00047 
00048 #include <moveit_msgs/GetPositionFK.h>
00049 #include <moveit_msgs/GetPositionIK.h>
00050 #include <moveit_msgs/GetKinematicSolverInfo.h>
00051 #include <moveit_msgs/MoveItErrorCodes.h>
00052 
00053 #include <kdl/chainfksolverpos_recursive.hpp>
00054 
00055 #include <boost/shared_ptr.hpp>
00056 
00057 namespace pr2_arm_kinematics
00058 {
00059   class PR2ArmKinematics
00060   {
00061     public:
00062 
00073     PR2ArmKinematics(bool create_transform_listener = true);
00074 
00075     virtual ~PR2ArmKinematics();
00076 
00081     bool isActive();
00082 
00088     virtual bool getPositionIK(moveit_msgs::GetPositionIK::Request &request,
00089                                moveit_msgs::GetPositionIK::Response &response);
00090 
00096     bool getIKSolverInfo(moveit_msgs::GetKinematicSolverInfo::Request &request,
00097                          moveit_msgs::GetKinematicSolverInfo::Response &response);
00098 
00104     bool getFKSolverInfo(moveit_msgs::GetKinematicSolverInfo::Request &request,
00105                          moveit_msgs::GetKinematicSolverInfo::Response &response);
00106 
00112     bool getPositionFK(moveit_msgs::GetPositionFK::Request &request,
00113                        moveit_msgs::GetPositionFK::Response &response);
00114 
00115     protected:
00116 
00117     
00118     bool getPositionIKHelper(moveit_msgs::GetPositionIK::Request &request,
00119                  moveit_msgs::GetPositionIK::Response &response);
00120 
00121     virtual bool transformPose(const std::string& des_frame,
00122                    const geometry_msgs::PoseStamped& pose_in,
00123                    geometry_msgs::PoseStamped& pose_out);
00124 
00125     bool active_;
00126     int free_angle_;
00127     urdf::Model robot_model_;
00128     double search_discretization_;
00129     ros::NodeHandle node_handle_, root_handle_;
00130     boost::shared_ptr<pr2_arm_kinematics::PR2ArmIKSolver> pr2_arm_ik_solver_;
00131     ros::ServiceServer ik_service_,fk_service_,ik_solver_info_service_,fk_solver_info_service_;
00132     tf::TransformListener* tf_;
00133     std::string root_name_;
00134     int dimension_;
00135     boost::shared_ptr<KDL::ChainFkSolverPos_recursive> jnt_to_pose_solver_;
00136     KDL::Chain kdl_chain_;
00137     moveit_msgs::KinematicSolverInfo ik_solver_info_, fk_solver_info_;
00138   };
00139 }
00140 
00141 #endif