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
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 <motion_planning_msgs/ArmNavigationErrorCodes.h>
00053
00054 #include <kdl/chainfksolverpos_recursive.hpp>
00055
00056 #include <boost/shared_ptr.hpp>
00057
00058 namespace pr2_arm_kinematics
00059 {
00060 class PR2ArmKinematics
00061 {
00062 public:
00063
00074 PR2ArmKinematics();
00075
00076 virtual ~PR2ArmKinematics(){};
00077
00082 bool isActive();
00083
00089 bool getPositionIK(kinematics_msgs::GetPositionIK::Request &request,
00090 kinematics_msgs::GetPositionIK::Response &response);
00091
00097 bool getIKSolverInfo(kinematics_msgs::GetKinematicSolverInfo::Request &request,
00098 kinematics_msgs::GetKinematicSolverInfo::Response &response);
00099
00105 bool getFKSolverInfo(kinematics_msgs::GetKinematicSolverInfo::Request &request,
00106 kinematics_msgs::GetKinematicSolverInfo::Response &response);
00107
00113 bool getPositionFK(kinematics_msgs::GetPositionFK::Request &request,
00114 kinematics_msgs::GetPositionFK::Response &response);
00115
00116 protected:
00117
00118 bool active_;
00119 int free_angle_;
00120 urdf::Model robot_model_;
00121 double search_discretization_;
00122 ros::NodeHandle node_handle_, root_handle_;
00123 boost::shared_ptr<pr2_arm_kinematics::PR2ArmIKSolver> pr2_arm_ik_solver_;
00124 ros::ServiceServer ik_service_,fk_service_,ik_solver_info_service_,fk_solver_info_service_;
00125 tf::TransformListener tf_;
00126 std::string root_name_;
00127 int dimension_;
00128 boost::shared_ptr<KDL::ChainFkSolverPos_recursive> jnt_to_pose_solver_;
00129 KDL::Chain kdl_chain_;
00130 kinematics_msgs::KinematicSolverInfo ik_solver_info_, fk_solver_info_;
00131 };
00132 }
00133
00134 #endif