Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 #include <stdio.h>
00034 #include <stdlib.h>
00035 #include <time.h>
00036 #include <ros/ros.h>
00037 #include <kinematics_msgs/GetPositionIK.h>
00038 #include <kinematics_msgs/GetPositionFK.h>
00039 #include <kinematics_msgs/GetKinematicSolverInfo.h>
00040 #include <kinematics_msgs/GetConstraintAwarePositionIK.h>
00041 
00042 #include <gtest/gtest.h>
00043 
00044 #define IK_NEAR 1e-4
00045 #define IK_NEAR_TRANSLATE 1e-5
00046 
00047 static const std::string ARM_FK_NAME = "/pr2_right_arm_kinematics/get_fk";
00048 static const std::string ARM_IK_NAME = "/pr2_right_arm_kinematics/get_ik";
00049 static const std::string ARM_COLLISION_IK_NAME = "/pr2_right_arm_kinematics/get_constraint_aware_ik";
00050 static const std::string ARM_QUERY_NAME = "/pr2_right_arm_kinematics/get_ik_solver_info";
00051 
00052 static const int NUM_TESTS = 1000;
00053 
00054 double gen_rand(double min, double max)
00055 {
00056   int rand_num = rand()%100+1;
00057   double result = min + (double)((max-min)*rand_num)/101.0;
00058   return result;
00059 }
00060 
00061 bool NOT_NEAR(const double &v1, const double &v2, const double &NEAR)
00062 {
00063   if(fabs(v1-v2) > NEAR)
00064     return true;
00065   return false;
00066 }
00067 
00068 TEST(PR2ArmIKWithCollisionNode, inverseKinematics)
00069 {
00070   srand ( time(NULL) ); 
00071   ros::NodeHandle rh;
00072   ros::service::waitForService(ARM_QUERY_NAME);
00073   ros::service::waitForService(ARM_FK_NAME);
00074   ros::service::waitForService(ARM_COLLISION_IK_NAME);
00075 
00076   ros::Duration(20.0).sleep();
00077 
00078   ros::ServiceClient query_client = rh.serviceClient<kinematics_msgs::GetKinematicSolverInfo>(ARM_QUERY_NAME);
00079   ros::ServiceClient fk_client = rh.serviceClient<kinematics_msgs::GetPositionFK>(ARM_FK_NAME);
00080   ros::ServiceClient ik_with_collision_client = rh.serviceClient<kinematics_msgs::GetConstraintAwarePositionIK>(ARM_COLLISION_IK_NAME);
00081   ros::ServiceClient ik_client = rh.serviceClient<kinematics_msgs::GetPositionIK>(ARM_IK_NAME);
00082 
00083   
00084   kinematics_msgs::GetKinematicSolverInfo::Request request;
00085   kinematics_msgs::GetKinematicSolverInfo::Response response;
00086             
00087   bool service_call = query_client.call(request, response);
00088   ASSERT_TRUE(service_call);
00089   ASSERT_TRUE(response.kinematic_solver_info.joint_names.size() == response.kinematic_solver_info.limits.size());
00090   ASSERT_TRUE(!response.kinematic_solver_info.link_names.empty());
00091 
00092   int num_joints;
00093   std::vector<double> min_limits, max_limits;
00094   num_joints = (int) response.kinematic_solver_info.joint_names.size();
00095   for(int i=0; i< num_joints; i++)
00096   {
00097     min_limits.push_back(response.kinematic_solver_info.limits[i].min_position);
00098     max_limits.push_back(response.kinematic_solver_info.limits[i].max_position);
00099   }
00100 
00101   kinematics_msgs::GetConstraintAwarePositionIK::Request  ik_request;
00102   kinematics_msgs::GetConstraintAwarePositionIK::Response ik_response;
00103 
00104   ik_request.ik_request.ik_seed_state.joint_state.name = response.kinematic_solver_info.joint_names;
00105   ik_request.ik_request.ik_seed_state.joint_state.position.resize(num_joints);
00106   ik_request.ik_request.ik_link_name = response.kinematic_solver_info.link_names[0];
00107   ik_request.timeout = ros::Duration(2.0);
00108   for(int i=0; i< num_joints; i++)
00109   {
00110     ik_request.ik_request.ik_seed_state.joint_state.position[i] = gen_rand(std::max(min_limits[i],-M_PI),std::min(max_limits[i],M_PI));
00111   }
00112 
00113   ik_request.ik_request.ik_link_name = "r_wrist_roll_link";
00114   ik_request.ik_request.pose_stamped.header.frame_id = "torso_lift_link";
00115   ik_request.ik_request.pose_stamped.pose.position.x = 0.45;
00116   ik_request.ik_request.pose_stamped.pose.position.y = 0.0;
00117   ik_request.ik_request.pose_stamped.pose.position.z = 0.0;
00118 
00119   ik_request.ik_request.pose_stamped.pose.orientation.x = 0.0;
00120   ik_request.ik_request.pose_stamped.pose.orientation.y = 0.0;
00121   ik_request.ik_request.pose_stamped.pose.orientation.z = 0.0;
00122   ik_request.ik_request.pose_stamped.pose.orientation.w = 1.0;
00123 
00124   bool ik_service_call = ik_with_collision_client.call(ik_request,ik_response);
00125   if(!ik_service_call)
00126   {
00127     ROS_ERROR("IK service call failed");
00128   }
00129   ROS_INFO("IK response code: %d",(int)ik_response.error_code.val);
00130   ROS_DEBUG("IK response: num positions %d, num solution joints %d",(int)ik_response.solution.joint_state.position.size(),(int)ik_response.solution.joint_state.name.size());
00131   ASSERT_TRUE(ik_response.error_code.val == ik_response.error_code.IK_LINK_IN_COLLISION);
00132 
00133 
00134   kinematics_msgs::GetPositionIK::Request  pos_ik_request;
00135   kinematics_msgs::GetPositionIK::Response pos_ik_response;
00136   pos_ik_request.ik_request = ik_request.ik_request;
00137   pos_ik_request.timeout = ik_request.timeout;
00138   bool ik_call = ik_client.call(pos_ik_request,pos_ik_response);
00139   ASSERT_TRUE(ik_call);
00140   ASSERT_TRUE(pos_ik_response.error_code.val == pos_ik_response.error_code.SUCCESS);
00141   ros::shutdown();
00142 }
00143 
00144 int main(int argc, char **argv){
00145   testing::InitGoogleTest(&argc, argv);
00146   ros::init (argc, argv, "pr2_ik_with_collision_regression_test");
00147   return RUN_ALL_TESTS();
00148 }