test_ik_regress.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 <pr2_arm_kinematics/pr2_arm_ik_solver.h>
00038 #include <pr2_arm_kinematics/pr2_arm_kinematics_utils.h>
00039 #include <kdl/chainfksolverpos_recursive.hpp>
00040 #include <moveit_msgs/MoveItErrorCodes.h>
00041 
00042 #include <gtest/gtest.h>
00043 
00044 
00045 
00046 #define IK_NEAR 1e-4
00047 #define IK_NEAR_TRANSLATE 1e-5
00048 using namespace pr2_arm_kinematics;
00049 using namespace KDL;
00050 
00051 double gen_rand(double min, double max)
00052 {
00053   int rand_num = rand()%100+1;
00054   double result = min + (double)((max-min)*rand_num)/101.0;
00055   return result;
00056 }
00057 
00058 TEST(PR2ArmIK, initialize)
00059 {
00060   ros::NodeHandle nh("pr2_ik_regression_test");
00061   urdf::Model robot_model;
00062   std::string tip_name,root_name,xml_string;
00063   int free_angle;
00064   double sd;
00065   ROS_INFO("Running test");
00066   EXPECT_TRUE(loadRobotModel(nh,robot_model,xml_string));
00067   nh.param<int>("free_angle",free_angle,2);
00068   nh.param<double>("search_discretization",sd,0.01);
00069 }
00070 
00071 bool NOT_NEAR(const double &v1, const double &v2, const double &NEAR)
00072 {
00073    if(fabs(v1-v2) > NEAR)
00074       return true;
00075    return false;
00076 }
00077 
00078 TEST(PR2ArmIK, inverseKinematics)
00079 {
00080   ros::NodeHandle nh("/pr2_ik_regression_test");
00081   urdf::Model robot_model;
00082   std::string tip_name,root_name,xml_string;
00083   int free_angle;
00084   double sd;
00085 
00086   EXPECT_TRUE(loadRobotModel(nh,robot_model,xml_string));
00087   nh.param<int>("free_angle",free_angle,2);
00088   nh.param<double>("search_discretization",sd,0.01);
00089 
00090   if (!nh.getParam("root_name", root_name)){
00091     ROS_ERROR("PR2IK: No root name found on parameter server");
00092   }
00093   if (!nh.getParam("tip_name", tip_name)){
00094     ROS_ERROR("PR2IK: No tip name found on parameter server");
00095   }
00096 
00097   pr2_arm_kinematics::PR2ArmIKSolver ik(robot_model,root_name,tip_name,sd,free_angle);
00098 
00099   KDL::Chain kdl_chain;
00100   EXPECT_TRUE(pr2_arm_kinematics::getKDLChain(xml_string,root_name,tip_name,kdl_chain));
00101 
00102   int num_tests = 10000;
00103   EXPECT_TRUE(ik.active_);
00104 
00105   KDL::ChainFkSolverPos_recursive *jnt_to_pose_solver;
00106   KDL::JntArray jnt_pos_in;
00107   KDL::JntArray jnt_pos_out;
00108   KDL::Frame p_out;
00109   KDL::Frame p_ik;
00110 
00111   srand ( time(NULL) ); // initialize random seed:
00112 
00113   jnt_to_pose_solver = new KDL::ChainFkSolverPos_recursive(kdl_chain);
00114   jnt_pos_in.resize(7);
00115   jnt_pos_out.resize(7);
00116 
00117   kinematics_msgs::KinematicSolverInfo chain_info;
00118   ik.getSolverInfo(chain_info);
00119 
00120   int num_solutions(0);
00121 
00122   for(int kk = 0; kk < num_tests; kk++)
00123   {
00124     for(int i=0; i < 7; i++)
00125     {
00126       jnt_pos_in(i) = gen_rand(std::max(chain_info.limits[i].min_position,-M_PI),std::min(chain_info.limits[i].max_position,M_PI));
00127       EXPECT_TRUE((jnt_pos_in(i) <= chain_info.limits[i].max_position));
00128       EXPECT_TRUE((jnt_pos_in(i) >= chain_info.limits[i].min_position));
00129     }
00130 
00131     if(jnt_to_pose_solver->JntToCart(jnt_pos_in,p_out) >=0)
00132     {
00133       bool ik_valid = (ik.CartToJnt(jnt_pos_in,p_out,jnt_pos_out) >= 0);
00134       if(ik_valid)
00135       {
00136         num_solutions++;
00137         jnt_to_pose_solver->JntToCart(jnt_pos_out,p_ik);
00138         for(int j=0; j< 3; j++)
00139         {
00140           EXPECT_NEAR(p_ik.M(j,0),p_out.M(j,0),IK_NEAR);
00141           EXPECT_NEAR(p_ik.M(j,1),p_out.M(j,1),IK_NEAR);
00142           EXPECT_NEAR(p_ik.M(j,2),p_out.M(j,2),IK_NEAR);
00143           EXPECT_NEAR(p_ik.p(j),p_out.p(j),IK_NEAR_TRANSLATE);
00144         }
00145       }
00146     }
00147   }
00148 
00149   bool success = ((double)num_solutions)/((double) num_tests) > 0.99;
00150   ROS_INFO("Success rate is %f",((double)num_solutions)/((double) num_tests));
00151   EXPECT_TRUE(success);
00152   delete jnt_to_pose_solver;
00153 }
00154 
00155 
00156 TEST(PR2ArmIK, inverseKinematicsSearch)
00157 {
00158   ros::NodeHandle nh("/pr2_ik_regression_test");
00159   urdf::Model robot_model;
00160   std::string tip_name,root_name,xml_string;
00161   int free_angle;
00162   double sd;
00163 
00164   EXPECT_TRUE(loadRobotModel(nh,robot_model,xml_string));
00165   nh.param<int>("free_angle",free_angle,2);
00166   nh.param<double>("search_discretization",sd,0.001);
00167   if (!nh.getParam("root_name", root_name)){
00168     ROS_ERROR("PR2IK: No root name found on parameter server");
00169   }
00170   if (!nh.getParam("tip_name", tip_name)){
00171     ROS_ERROR("PR2IK: No tip name found on parameter server");
00172   }
00173 
00174 
00175   pr2_arm_kinematics::PR2ArmIKSolver ik(robot_model,root_name,tip_name,sd,free_angle);
00176 
00177   KDL::Chain kdl_chain;
00178   EXPECT_TRUE(pr2_arm_kinematics::getKDLChain(xml_string,root_name,tip_name,kdl_chain));
00179 
00180   kinematics_msgs::KinematicSolverInfo chain_info;
00181   ik.getSolverInfo(chain_info);
00182 
00183   int num_tests = 10000;
00184   KDL::ChainFkSolverPos_recursive *jnt_to_pose_solver;
00185   KDL::JntArray jnt_pos_in;
00186   KDL::JntArray jnt_pos_test;
00187   std::vector<KDL::JntArray> jnt_pos_out;
00188   KDL::Frame p_out;
00189   KDL::Frame p_ik;
00190 
00191   srand ( time(NULL) );
00192 
00193   jnt_to_pose_solver = new KDL::ChainFkSolverPos_recursive(kdl_chain);
00194   jnt_pos_in.resize(7);
00195   jnt_pos_test.resize(7);
00196 
00197   int num_solutions(0);
00198 
00199   for(int kk = 0; kk < num_tests; kk++)
00200   {
00201     ROS_INFO("Test: %d",kk);
00202     for(int i=0; i < 7; i++)
00203     {
00204       jnt_pos_in(i) = gen_rand(std::max(chain_info.limits[i].min_position,-M_PI),std::min(chain_info.limits[i].max_position,M_PI));
00205       EXPECT_TRUE((jnt_pos_in(i) <= chain_info.limits[i].max_position));
00206       EXPECT_TRUE((jnt_pos_in(i) >= chain_info.limits[i].min_position));
00207     }
00208     for(int i=0; i < 7; i++)
00209     {
00210       jnt_pos_test(i) = gen_rand(std::max(chain_info.limits[i].min_position,-M_PI),std::min(chain_info.limits[i].max_position,M_PI));
00211       EXPECT_TRUE((jnt_pos_test(i) <= chain_info.limits[i].max_position));
00212       EXPECT_TRUE((jnt_pos_test(i) >= chain_info.limits[i].min_position));
00213       }
00214     if(jnt_to_pose_solver->JntToCart(jnt_pos_in,p_out) >=0)
00215     {
00216       moveit_msgs::MoveItErrorCodes error_code;
00217       bool ik_valid = (ik.CartToJntSearch(jnt_pos_test,p_out,jnt_pos_out,10) >= 0);
00218       if(ik_valid)
00219       {
00220         num_solutions++;
00221         for(int k=0; k < (int)jnt_pos_out.size(); k++)
00222         {
00223           jnt_to_pose_solver->JntToCart(jnt_pos_out[k],p_ik);
00224           for(int j=0; j< 3; j++)
00225           {
00226             EXPECT_NEAR(p_ik.M(j,0),p_out.M(j,0),IK_NEAR);
00227             EXPECT_NEAR(p_ik.M(j,1),p_out.M(j,1),IK_NEAR);
00228             EXPECT_NEAR(p_ik.M(j,2),p_out.M(j,2),IK_NEAR);
00229             EXPECT_NEAR(p_ik.p(j),p_out.p(j),IK_NEAR_TRANSLATE);
00230           }
00231         }
00232       }
00233       else
00234       {
00235         ROS_INFO("Failed solution");
00236         for(int m=0; m < 3; m++)
00237         {
00238           printf("%f %f %f %f\n",p_out.M(m,0),p_out.M(m,1),p_out.M(m,2),p_out.p(m));
00239         }
00240         printf("\n");
00241         ROS_INFO("Original joint values");
00242           for(int n = 0; n< 7; n++)
00243           {
00244             printf("%f ",jnt_pos_in(n));
00245           }
00246           printf("\n");
00247           ROS_INFO("Guess: %f",jnt_pos_test(2));
00248         ROS_INFO("\n\n\n");
00249       }
00250     }
00251   }
00252   bool success = ((double)num_solutions)/((double) num_tests) > 0.99;
00253   ROS_INFO("Success rate is %f",((double)num_solutions)/((double) num_tests));
00254   EXPECT_TRUE(success);
00255   delete jnt_to_pose_solver;
00256 }
00257 
00258 
00259 int main(int argc, char **argv)
00260 {
00261   testing::InitGoogleTest(&argc, argv);
00262   ros::init (argc, argv, "pr2_ik_regression_test");
00263   return RUN_ALL_TESTS();
00264 }


pr2_arm_ik_tests
Author(s): Sachin Chitta
autogenerated on Mon Oct 6 2014 11:16:25