test_ik_with_constraints.cpp
Go to the documentation of this file.
00001 //Software License Agreement (BSD License)
00002 
00003 //Copyright (c) 2008, Willow Garage, Inc.
00004 //All rights reserved.
00005 
00006 //Redistribution and use in source and binary forms, with or without
00007 //modification, are permitted provided that the following conditions
00008 //are met:
00009 
00010 // * Redistributions of source code must retain the above copyright
00011 //   notice, this list of conditions and the following disclaimer.
00012 // * Redistributions in binary form must reproduce the above
00013 //   copyright notice, this list of conditions and the following
00014 //   disclaimer in the documentation and/or other materials provided
00015 //   with the distribution.
00016 // * Neither the name of Willow Garage, Inc. nor the names of its
00017 //   contributors may be used to endorse or promote products derived
00018 //   from this software without specific prior written permission.
00019 
00020 //THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 //"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 //LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 //FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 //COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 //INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 //BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 //LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 //CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 //LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 //ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 //POSSIBILITY OF SUCH DAMAGE.
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) ); // initialize random seed
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   // define the service messages
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 
00125   //Setup visibility constraints  
00126   motion_planning_msgs::PositionConstraint pc;
00127   pc.header.frame_id = "torso_lift_link";
00128   pc.header.stamp = ros::Time();
00129   pc.link_name = "r_elbow_flex_link";
00130   pc.position.x = 0.45;
00131   pc.position.y = 0.0;
00132   pc.position.z = 1.0;
00133 
00134   pc.constraint_region_shape.type = geometric_shapes_msgs::Shape::BOX;
00135   pc.constraint_region_shape.dimensions.push_back(1.8);
00136   pc.constraint_region_shape.dimensions.push_back(1.8);
00137   pc.constraint_region_shape.dimensions.push_back(1.8);
00138   pc.constraint_region_orientation.w = 1.0;
00139   ik_request.constraints.position_constraints.push_back(pc);
00140 
00141 
00142   bool ik_service_call = ik_with_collision_client.call(ik_request,ik_response);
00143   if(!ik_service_call)
00144   {
00145     ROS_ERROR("IK service call failed");
00146   }
00147   ROS_INFO("IK response code: %d",(int)ik_response.error_code.val);
00148   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());
00149   ASSERT_TRUE(ik_response.error_code.val == ik_response.error_code.SUCCESS);
00150 
00151 
00152 
00153   kinematics_msgs::GetPositionFK::Request  fk_request;
00154   kinematics_msgs::GetPositionFK::Response fk_response;
00155   fk_request.header.frame_id = "torso_lift_link";
00156   fk_request.fk_link_names.resize(1);
00157   fk_request.fk_link_names[0] = "r_elbow_flex_link";
00158   fk_request.robot_state.joint_state.position = ik_response.solution.joint_state.position;
00159   fk_request.robot_state.joint_state.name = ik_response.solution.joint_state.name;
00160   if(fk_client.call(fk_request, fk_response))
00161   {
00162     if(fk_response.error_code.val == fk_response.error_code.SUCCESS)
00163     {
00164       for(unsigned int i=0; i < fk_response.pose_stamped.size(); i ++)
00165       {
00166         ROS_INFO_STREAM("Link    : " << fk_response.fk_link_names[i].c_str());
00167         ROS_INFO_STREAM("Position: " << 
00168           fk_response.pose_stamped[i].pose.position.x << "," <<  
00169           fk_response.pose_stamped[i].pose.position.y << "," << 
00170           fk_response.pose_stamped[i].pose.position.z);
00171         ROS_INFO("Orientation: %f %f %f %f",
00172           fk_response.pose_stamped[i].pose.orientation.x,
00173           fk_response.pose_stamped[i].pose.orientation.y,
00174           fk_response.pose_stamped[i].pose.orientation.z,
00175           fk_response.pose_stamped[i].pose.orientation.w);
00176       } 
00177     }
00178     else
00179     {
00180       ROS_ERROR("Forward kinematics failed");
00181     }
00182   }
00183   else
00184   {
00185     ROS_ERROR("Forward kinematics service call failed");
00186   }
00187 
00188   kinematics_msgs::GetPositionIK::Request  pos_ik_request;
00189   kinematics_msgs::GetPositionIK::Response pos_ik_response;
00190   pos_ik_request.ik_request = ik_request.ik_request;
00191   pos_ik_request.timeout = ik_request.timeout;
00192   bool ik_call = ik_client.call(pos_ik_request,pos_ik_response);
00193   ASSERT_TRUE(ik_call);
00194   ASSERT_TRUE(pos_ik_response.error_code.val == pos_ik_response.error_code.SUCCESS);
00195   ros::shutdown();
00196 }
00197 
00198 int main(int argc, char **argv){
00199   testing::InitGoogleTest(&argc, argv);
00200   ros::init (argc, argv, "pr2_ik_with_collision_regression_test");
00201   return RUN_ALL_TESTS();
00202 }


pr2_arm_ik_tests
Author(s): Sachin Chitta
autogenerated on Sat Dec 28 2013 17:24:01