$search
00001 #include <ros/ros.h> 00002 #include <kinematics_msgs/GetKinematicSolverInfo.h> 00003 #include <kinematics_msgs/GetConstraintAwarePositionIK.h> 00004 #include <arm_navigation_msgs/SetPlanningSceneDiff.h> 00005 00006 static const std::string SET_PLANNING_SCENE_DIFF_NAME = "/environment_server/set_planning_scene_diff"; 00007 00008 int main(int argc, char **argv){ 00009 ros::init (argc, argv, "get_fk"); 00010 ros::NodeHandle rh; 00011 00012 ros::service::waitForService("pr2_right_arm_kinematics/get_ik_solver_info"); 00013 ros::service::waitForService("pr2_right_arm_kinematics/get_constraint_aware_ik"); 00014 00015 ros::ServiceClient query_client = rh.serviceClient<kinematics_msgs::GetKinematicSolverInfo>("pr2_right_arm_kinematics/get_ik_solver_info"); 00016 ros::ServiceClient ik_client = rh.serviceClient<kinematics_msgs::GetConstraintAwarePositionIK>("pr2_right_arm_kinematics/get_constraint_aware_ik"); 00017 ros::ServiceClient set_planning_scene_diff_client = rh.serviceClient<arm_navigation_msgs::SetPlanningSceneDiff>(SET_PLANNING_SCENE_DIFF_NAME); 00018 00019 arm_navigation_msgs::SetPlanningSceneDiff::Request planning_scene_req; 00020 arm_navigation_msgs::SetPlanningSceneDiff::Response planning_scene_res; 00021 00022 if(!set_planning_scene_diff_client.call(planning_scene_req, planning_scene_res)) { 00023 ROS_WARN("Can't get planning scene"); 00024 return -1; 00025 } 00026 00027 // define the service messages 00028 kinematics_msgs::GetKinematicSolverInfo::Request request; 00029 kinematics_msgs::GetKinematicSolverInfo::Response response; 00030 00031 if(query_client.call(request,response)) 00032 { 00033 for(unsigned int i=0; i< response.kinematic_solver_info.joint_names.size(); i++) 00034 { 00035 ROS_DEBUG("Joint: %d %s",i,response.kinematic_solver_info.joint_names[i].c_str()); 00036 } 00037 } 00038 else 00039 { 00040 ROS_ERROR("Could not call query service"); 00041 ros::shutdown(); 00042 exit(-1); 00043 } 00044 00045 // define the service messages 00046 kinematics_msgs::GetConstraintAwarePositionIK::Request gpik_req; 00047 kinematics_msgs::GetConstraintAwarePositionIK::Response gpik_res; 00048 00049 gpik_req.timeout = ros::Duration(5.0); 00050 gpik_req.ik_request.ik_link_name = "r_wrist_roll_link"; 00051 00052 gpik_req.ik_request.pose_stamped.header.frame_id = "torso_lift_link"; 00053 gpik_req.ik_request.pose_stamped.pose.position.x = 0.75; 00054 gpik_req.ik_request.pose_stamped.pose.position.y = -0.188; 00055 gpik_req.ik_request.pose_stamped.pose.position.z = 0.0; 00056 00057 gpik_req.ik_request.pose_stamped.pose.orientation.x = 0.0; 00058 gpik_req.ik_request.pose_stamped.pose.orientation.y = 0.0; 00059 gpik_req.ik_request.pose_stamped.pose.orientation.z = 0.0; 00060 gpik_req.ik_request.pose_stamped.pose.orientation.w = 1.0; 00061 00062 gpik_req.ik_request.ik_seed_state.joint_state.position.resize(response.kinematic_solver_info.joint_names.size()); 00063 gpik_req.ik_request.ik_seed_state.joint_state.name = response.kinematic_solver_info.joint_names; 00064 00065 for(unsigned int i=0; i< response.kinematic_solver_info.joint_names.size(); i++) 00066 { 00067 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; 00068 } 00069 if(ik_client.call(gpik_req, gpik_res)) 00070 { 00071 if(gpik_res.error_code.val == gpik_res.error_code.SUCCESS) 00072 { 00073 for(unsigned int i=0; i < gpik_res.solution.joint_state.name.size(); i ++) 00074 { 00075 ROS_INFO("Joint: %s %f",gpik_res.solution.joint_state.name[i].c_str(),gpik_res.solution.joint_state.position[i]); 00076 } 00077 } 00078 else 00079 { 00080 ROS_ERROR("Inverse kinematics failed"); 00081 } 00082 } 00083 else 00084 { 00085 ROS_ERROR("Inverse kinematics service call failed"); 00086 } 00087 ros::shutdown(); 00088 }