$search
00001 #include <ros/ros.h> 00002 #include <kinematics_msgs/GetKinematicSolverInfo.h> 00003 #include <kinematics_msgs/GetPositionIK.h> 00004 #include <kinematics_msgs/GetPositionFK.h> 00005 00006 int main(int argc, char **argv){ 00007 ros::init (argc, argv, "get_ik"); 00008 ros::NodeHandle rh; 00009 00010 ros::service::waitForService("pr2_kinematics_right_arm/get_ik_solver_info"); 00011 ros::service::waitForService("pr2_kinematics_right_arm/get_ik"); 00012 00013 ros::ServiceClient query_client = rh.serviceClient<kinematics_msgs::GetKinematicSolverInfo>("pr2_kinematics_right_arm/get_ik_solver_info"); 00014 ros::ServiceClient ik_client = rh.serviceClient<kinematics_msgs::GetPositionIK>("pr2_kinematics_right_arm/get_ik"); 00015 ros::ServiceClient fk_client = rh.serviceClient 00016 <kinematics_msgs::GetPositionFK>("pr2_kinematics_right_arm/get_fk"); 00017 00018 // define the service messages 00019 kinematics_msgs::GetKinematicSolverInfo::Request request; 00020 kinematics_msgs::GetKinematicSolverInfo::Response response; 00021 00022 if(query_client.call(request,response)) 00023 { 00024 for(unsigned int i=0; i< response.kinematic_solver_info.joint_names.size(); i++) 00025 { 00026 ROS_DEBUG("Joint: %d %s",i,response.kinematic_solver_info.joint_names[i].c_str()); 00027 } 00028 } 00029 else 00030 { 00031 ROS_ERROR("Could not call query service"); 00032 ros::shutdown(); 00033 exit(-1); 00034 } 00035 // define the service messages 00036 kinematics_msgs::GetPositionIK::Request gpik_req; 00037 kinematics_msgs::GetPositionIK::Response gpik_res; 00038 gpik_req.timeout = ros::Duration(5.0); 00039 gpik_req.ik_request.ik_link_name = "r_wrist_roll_link"; 00040 00041 gpik_req.ik_request.pose_stamped.header.frame_id = "base_link"; 00042 gpik_req.ik_request.pose_stamped.pose.position.x = 0.311310444845; 00043 gpik_req.ik_request.pose_stamped.pose.position.y = 0.289857826894; 00044 gpik_req.ik_request.pose_stamped.pose.position.z = 0.809285310181; 00045 00046 gpik_req.ik_request.pose_stamped.pose.orientation.x =0.383628180569 ; 00047 gpik_req.ik_request.pose_stamped.pose.orientation.y = 0.563580225645; 00048 gpik_req.ik_request.pose_stamped.pose.orientation.z =0.581314277544 ; 00049 gpik_req.ik_request.pose_stamped.pose.orientation.w =0.444162649329 ; 00050 gpik_req.ik_request.ik_seed_state.joint_state.position.resize(response.kinematic_solver_info.joint_names.size()); 00051 gpik_req.ik_request.ik_seed_state.joint_state.name = response.kinematic_solver_info.joint_names; 00052 for(unsigned int i=0; i< response.kinematic_solver_info.joint_names.size(); i++) 00053 { 00054 gpik_req.ik_request.ik_seed_state.joint_state.position[i] = (response.kinematic_solver_info.limits[i].min_position + response.kinematic_solver_info.limits[i].max_position)/2.0; 00055 } 00056 00057 gpik_req.ik_request.ik_seed_state.joint_state.position[0] = -2.1060293903819898; 00058 gpik_req.ik_request.ik_seed_state.joint_state.position[1] = 0.26298790696529961; 00059 gpik_req.ik_request.ik_seed_state.joint_state.position[2] = -3.6540052314061247; 00060 gpik_req.ik_request.ik_seed_state.joint_state.position[3] = -2.0685583319566816; 00061 gpik_req.ik_request.ik_seed_state.joint_state.position[4] = -0.57887736940987111; 00062 gpik_req.ik_request.ik_seed_state.joint_state.position[5] = -1.4212910723690739; 00063 gpik_req.ik_request.ik_seed_state.joint_state.position[6] = -3.2345250184874357; 00064 00065 if(ik_client.call(gpik_req, gpik_res)) 00066 { 00067 if(gpik_res.error_code.val == gpik_res.error_code.SUCCESS) 00068 for(unsigned int i=0; i < gpik_res.solution.joint_state.name.size(); i ++) 00069 ROS_INFO("Joint: %s %f",gpik_res.solution.joint_state.name[i].c_str(),gpik_res.solution.joint_state.position[i]); 00070 else 00071 ROS_ERROR("Inverse kinematics failed"); 00072 } 00073 else 00074 ROS_ERROR("Inverse kinematics service call failed"); 00075 00076 00077 kinematics_msgs::GetPositionFK::Request fk_request; 00078 kinematics_msgs::GetPositionFK::Response fk_response; 00079 fk_request.header.frame_id = "base_link"; 00080 fk_request.fk_link_names.resize(1); 00081 fk_request.fk_link_names[0] = "r_wrist_roll_link"; 00082 00083 fk_request.robot_state.joint_state.position = gpik_res.solution.joint_state.position; 00084 fk_request.robot_state.joint_state.name = gpik_res.solution.joint_state.name; 00085 00086 if(fk_client.call(fk_request, fk_response)) 00087 { 00088 if(fk_response.error_code.val == fk_response.error_code.SUCCESS) 00089 { 00090 for(unsigned int i=0; i < fk_response.pose_stamped.size(); i ++) 00091 { 00092 ROS_INFO_STREAM("Link: " << fk_response.fk_link_names[i].c_str()); 00093 ROS_INFO_STREAM("Position: " << 00094 fk_response.pose_stamped[i].pose.position.x << "," << 00095 fk_response.pose_stamped[i].pose.position.y << "," << 00096 fk_response.pose_stamped[i].pose.position.z); 00097 ROS_INFO("Orientation: %f %f %f %f", 00098 fk_response.pose_stamped[i].pose.orientation.x, 00099 fk_response.pose_stamped[i].pose.orientation.y, 00100 fk_response.pose_stamped[i].pose.orientation.z, 00101 fk_response.pose_stamped[i].pose.orientation.w); 00102 } 00103 } 00104 else 00105 { 00106 ROS_ERROR("Forward kinematics failed"); 00107 } 00108 } 00109 else 00110 { 00111 ROS_ERROR("Forward kinematics service call failed"); 00112 } 00113 00114 ros::shutdown(); 00115 }