Go to the documentation of this file.00001 #include <ros/ros.h>
00002
00003 #include <kinematics_msgs/GetKinematicSolverInfo.h>
00004 #include <kinematics_msgs/GetConstraintAwarePositionIK.h>
00005 #include <arm_navigation_msgs/SetPlanningSceneDiff.h>
00006
00007 static const std::string ARM_COLLISION_IK_NAME = "/pr2_right_arm_kinematics/get_constraint_aware_ik";
00008 static const std::string ARM_QUERY_NAME = "/pr2_right_arm_kinematics/get_ik_solver_info";
00009 static const std::string SET_PLANNING_SCENE_DIFF_NAME = "/environment_server/set_planning_scene_diff";
00010
00011 int main(int argc, char **argv){
00012 ros::init (argc, argv, "get_fk");
00013 ros::NodeHandle rh;
00014
00015 ros::service::waitForService(ARM_QUERY_NAME);
00016 ros::service::waitForService(ARM_COLLISION_IK_NAME);
00017 ros::service::waitForService(SET_PLANNING_SCENE_DIFF_NAME);
00018
00019 ros::ServiceClient set_planning_scene_diff_client = rh.serviceClient<arm_navigation_msgs::SetPlanningSceneDiff>(SET_PLANNING_SCENE_DIFF_NAME);
00020 ros::ServiceClient query_client = rh.serviceClient<kinematics_msgs::GetKinematicSolverInfo>(ARM_QUERY_NAME);
00021 ros::ServiceClient ik_with_collision_client = rh.serviceClient<kinematics_msgs::GetConstraintAwarePositionIK>(ARM_COLLISION_IK_NAME);
00022
00023 arm_navigation_msgs::SetPlanningSceneDiff::Request planning_scene_req;
00024 arm_navigation_msgs::SetPlanningSceneDiff::Response planning_scene_res;
00025
00026 arm_navigation_msgs::CollisionOperation coll;
00027 coll.object1 = "r_end_effector";
00028 coll.object2 = "l_end_effector";
00029 coll.operation = coll.DISABLE;
00030
00031 planning_scene_req.operations.collision_operations.push_back(coll);
00032 planning_scene_req.planning_scene_diff.robot_state.multi_dof_joint_state.stamp = ros::Time::now();
00033 planning_scene_req.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names.push_back("world_joint");
00034 planning_scene_req.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids.push_back("odom_combined");
00035 planning_scene_req.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids.push_back("base_footprint");
00036 planning_scene_req.planning_scene_diff.robot_state.multi_dof_joint_state.poses.resize(1);
00037 planning_scene_req.planning_scene_diff.robot_state.multi_dof_joint_state.poses[0].position.x = 4.0;
00038 planning_scene_req.planning_scene_diff.robot_state.multi_dof_joint_state.poses[0].orientation.w = 1.0;
00039
00040 if(!set_planning_scene_diff_client.call(planning_scene_req, planning_scene_res)) {
00041 ROS_WARN("Can't get planning scene");
00042 return -1;
00043 }
00044
00045
00046 kinematics_msgs::GetKinematicSolverInfo::Request request;
00047 kinematics_msgs::GetKinematicSolverInfo::Response response;
00048
00049 if(query_client.call(request,response))
00050 {
00051 for(unsigned int i=0; i< response.kinematic_solver_info.joint_names.size(); i++)
00052 {
00053 ROS_DEBUG("Joint: %d %s",i,response.kinematic_solver_info.joint_names[i].c_str());
00054 }
00055 }
00056 else
00057 {
00058 ROS_ERROR("Could not call query service");
00059 ros::shutdown();
00060 exit(-1);
00061 }
00062
00063
00064 kinematics_msgs::GetConstraintAwarePositionIK::Request gpik_req;
00065 kinematics_msgs::GetConstraintAwarePositionIK::Response gpik_res;
00066
00067 gpik_req.timeout = ros::Duration(5.0);
00068 gpik_req.ik_request.ik_link_name = "r_wrist_roll_link";
00069
00070 gpik_req.ik_request.pose_stamped.header.frame_id = "odom_combined";
00071 gpik_req.ik_request.pose_stamped.pose.position.x = 4.75;
00072 gpik_req.ik_request.pose_stamped.pose.position.y = -0.188;
00073 gpik_req.ik_request.pose_stamped.pose.position.z = .94;
00074
00075 gpik_req.ik_request.pose_stamped.pose.orientation.x = 0.0;
00076 gpik_req.ik_request.pose_stamped.pose.orientation.y = 0.0;
00077 gpik_req.ik_request.pose_stamped.pose.orientation.z = 0.0;
00078 gpik_req.ik_request.pose_stamped.pose.orientation.w = 1.0;
00079
00080 gpik_req.ik_request.ik_seed_state.joint_state.position.resize(response.kinematic_solver_info.joint_names.size());
00081 gpik_req.ik_request.ik_seed_state.joint_state.name = response.kinematic_solver_info.joint_names;
00082
00083 for(unsigned int i=0; i< response.kinematic_solver_info.joint_names.size(); i++)
00084 {
00085 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;
00086 }
00087 if(ik_with_collision_client.call(gpik_req, gpik_res))
00088 {
00089 if(gpik_res.error_code.val == gpik_res.error_code.SUCCESS)
00090 {
00091 for(unsigned int i=0; i < gpik_res.solution.joint_state.name.size(); i ++)
00092 {
00093 ROS_INFO("Joint: %s %f",gpik_res.solution.joint_state.name[i].c_str(),gpik_res.solution.joint_state.position[i]);
00094 }
00095 }
00096 else
00097 {
00098 ROS_ERROR("Inverse kinematics failed");
00099 }
00100 }
00101 else
00102 {
00103 ROS_ERROR("Inverse kinematics service call failed");
00104 }
00105 ros::shutdown();
00106 }