get_fk.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <kinematics_msgs/GetKinematicSolverInfo.h>
00003 #include <kinematics_msgs/GetPositionFK.h>
00004 
00005 int main(int argc, char **argv){
00006   ros::init (argc, argv, "get_fk");
00007   ros::NodeHandle rh;
00008 
00009   ros::service::waitForService("pr2_right_arm_kinematics/get_fk_solver_info");
00010   ros::service::waitForService("pr2_right_arm_kinematics/get_fk");
00011 
00012   ros::ServiceClient query_client = 
00013     rh.serviceClient<kinematics_msgs::GetKinematicSolverInfo>
00014     ("pr2_right_arm_kinematics/get_fk_solver_info");
00015   ros::ServiceClient fk_client = rh.serviceClient
00016     <kinematics_msgs::GetPositionFK>("pr2_right_arm_kinematics/get_fk");
00017 
00018   // define the service messages
00019   kinematics_msgs::GetKinematicSolverInfo::Request request;
00020   kinematics_msgs::GetKinematicSolverInfo::Response response;
00021   if(query_client.call(request,response))
00022   {
00023     for(unsigned int i=0; 
00024         i< response.kinematic_solver_info.joint_names.size(); i++)
00025     {
00026       ROS_DEBUG("Joint: %d %s", i,
00027        response.kinematic_solver_info.joint_names[i].c_str());
00028     }
00029   }
00030   else
00031   {
00032     ROS_ERROR("Could not call query service");
00033     ros::shutdown();
00034     exit(1);
00035   }
00036   // define the service messages
00037   kinematics_msgs::GetPositionFK::Request  fk_request;
00038   kinematics_msgs::GetPositionFK::Response fk_response;
00039   fk_request.header.frame_id = "torso_lift_link";
00040   fk_request.fk_link_names.resize(2);
00041   fk_request.fk_link_names[0] = "r_wrist_roll_link";
00042   fk_request.fk_link_names[1] = "r_elbow_flex_link";
00043   fk_request.robot_state.joint_state.position.resize
00044     (response.kinematic_solver_info.joint_names.size());
00045   fk_request.robot_state.joint_state.name = 
00046     response.kinematic_solver_info.joint_names;
00047   for(unsigned int i=0; 
00048       i< response.kinematic_solver_info.joint_names.size(); i++)
00049   {
00050     fk_request.robot_state.joint_state.position[i] = 0.5;
00051   }
00052   if(fk_client.call(fk_request, fk_response))
00053   {
00054     if(fk_response.error_code.val == fk_response.error_code.SUCCESS)
00055     {
00056       for(unsigned int i=0; i < fk_response.pose_stamped.size(); i ++)
00057       {
00058         ROS_INFO_STREAM("Link    : " << fk_response.fk_link_names[i].c_str());
00059         ROS_INFO_STREAM("Position: " << 
00060           fk_response.pose_stamped[i].pose.position.x << "," <<  
00061           fk_response.pose_stamped[i].pose.position.y << "," << 
00062           fk_response.pose_stamped[i].pose.position.z);
00063         ROS_INFO("Orientation: %f %f %f %f",
00064           fk_response.pose_stamped[i].pose.orientation.x,
00065           fk_response.pose_stamped[i].pose.orientation.y,
00066           fk_response.pose_stamped[i].pose.orientation.z,
00067           fk_response.pose_stamped[i].pose.orientation.w);
00068       } 
00069     }
00070     else
00071     {
00072       ROS_ERROR("Forward kinematics failed");
00073     }
00074   }
00075   else
00076   {
00077     ROS_ERROR("Forward kinematics service call failed");
00078   }
00079   ros::shutdown();
00080 }


pr2_arm_navigation_tutorials
Author(s): Sachin Chitta
autogenerated on Tue Apr 22 2014 19:29:47