get_ik.cpp
Go to the documentation of this file.
00001 //
00002 // Copied from
00003 // http://www.ros.org/wiki/pr2_kinematics/Tutorials/Tutorial%204
00004 //
00005 
00006 
00007 #include <ros/ros.h>
00008 #include <kinematics_msgs/GetKinematicSolverInfo.h>
00009 #include <kinematics_msgs/GetPositionIK.h>
00010 
00011 int main(int argc, char **argv){
00012     ros::init (argc, argv, "get_ik");
00013     ros::NodeHandle rh;
00014 
00015     ros::service::waitForService("pr2_right_arm_kinematics/get_ik_solver_info");
00016     ros::service::waitForService("pr2_right_arm_kinematics/get_ik");
00017 
00018     ros::ServiceClient query_client = rh.serviceClient<kinematics_msgs::GetKinematicSolverInfo>("pr2_right_arm_kinematics/get_ik_solver_info");
00019     ros::ServiceClient ik_client = rh.serviceClient<kinematics_msgs::GetPositionIK>("pr2_right_arm_kinematics/get_ik");
00020 
00021     // define the service messages
00022     kinematics_msgs::GetKinematicSolverInfo::Request request;
00023     kinematics_msgs::GetKinematicSolverInfo::Response response;
00024 
00025     if(query_client.call(request,response))
00026     {
00027         for(unsigned int i=0; i< response.kinematic_solver_info.joint_names.size(); i++)
00028         {
00029             ROS_DEBUG("Joint: %d %s",i,response.kinematic_solver_info.joint_names[i].c_str());
00030         }
00031     }
00032     else
00033     {
00034         ROS_ERROR("Could not call query service");
00035         ros::shutdown();
00036         exit(1);
00037     }
00038     // define the service messages
00039     kinematics_msgs::GetPositionIK::Request  gpik_req;
00040     kinematics_msgs::GetPositionIK::Response gpik_res;
00041     gpik_req.timeout = ros::Duration(5.0);
00042     gpik_req.ik_request.ik_link_name = "r_wrist_roll_link";
00043 
00044     gpik_req.ik_request.pose_stamped.header.frame_id = "torso_lift_link";
00045     gpik_req.ik_request.pose_stamped.pose.position.x = 0.75;
00046     gpik_req.ik_request.pose_stamped.pose.position.y = -0.188;
00047     gpik_req.ik_request.pose_stamped.pose.position.z = 0.0;
00048 
00049     gpik_req.ik_request.pose_stamped.pose.orientation.x = 0.0;
00050     gpik_req.ik_request.pose_stamped.pose.orientation.y = 0.0;
00051     gpik_req.ik_request.pose_stamped.pose.orientation.z = 0.0;
00052     gpik_req.ik_request.pose_stamped.pose.orientation.w = 1.0;
00053     gpik_req.ik_request.ik_seed_state.joint_state.position.resize(response.kinematic_solver_info.joint_names.size());
00054     gpik_req.ik_request.ik_seed_state.joint_state.name = response.kinematic_solver_info.joint_names;
00055     for(unsigned int i=0; i< response.kinematic_solver_info.joint_names.size(); i++)
00056     {
00057         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;
00058     }
00059     if(ik_client.call(gpik_req, gpik_res))
00060     {
00061         if(gpik_res.error_code.val == gpik_res.error_code.SUCCESS)
00062             for(unsigned int i=0; i < gpik_res.solution.joint_state.name.size(); i ++)
00063                 ROS_INFO("Joint: %s %f",gpik_res.solution.joint_state.name[i].c_str(),gpik_res.solution.joint_state.position[i]);
00064         else
00065             ROS_ERROR("Inverse kinematics failed");
00066     }
00067     else
00068         ROS_ERROR("Inverse kinematics service call failed");
00069     ros::shutdown();
00070 }
00071 
00072 
00073 
00074 
00075 


hrl_pr2_kinematics_tutorials
Author(s): Advait Jain (Healthcare Robotics Lab)
autogenerated on Wed Nov 27 2013 12:09:35