test_ik_regress.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Sachin Chitta */
00036 
00037 #include <stdio.h>
00038 #include <stdlib.h>
00039 #include <time.h>
00040 #include <ros/ros.h>
00041 #include <pr2_arm_kinematics/pr2_arm_ik_solver.h>
00042 #include <pr2_arm_kinematics/pr2_arm_kinematics_utils.h>
00043 #include <kdl/chainfksolverpos_recursive.hpp>
00044 #include <moveit_msgs/MoveItErrorCodes.h>
00045 
00046 #include <gtest/gtest.h>
00047 
00048 
00049 
00050 #define IK_NEAR 1e-4
00051 #define IK_NEAR_TRANSLATE 1e-5
00052 using namespace pr2_arm_kinematics;
00053 using namespace KDL;
00054 
00055 double gen_rand(double min, double max)
00056 {
00057   int rand_num = rand()%100+1;
00058   double result = min + (double)((max-min)*rand_num)/101.0;
00059   return result;
00060 }
00061 
00062 TEST(PR2ArmIK, initialize)
00063 {
00064   ros::NodeHandle nh("pr2_ik_regression_test");
00065   urdf::Model robot_model;
00066   std::string tip_name,root_name,xml_string;
00067   int free_angle;
00068   double sd;
00069   ROS_INFO("Running test");
00070   EXPECT_TRUE(loadRobotModel(nh,robot_model,xml_string));
00071   nh.param<int>("free_angle",free_angle,2);
00072   nh.param<double>("search_discretization",sd,0.01);
00073 }
00074 
00075 bool NOT_NEAR(const double &v1, const double &v2, const double &NEAR)
00076 {
00077    if(fabs(v1-v2) > NEAR)
00078       return true;
00079    return false;
00080 }
00081 
00082 TEST(PR2ArmIK, inverseKinematics)
00083 {
00084   ros::NodeHandle nh("/pr2_ik_regression_test");
00085   urdf::Model robot_model;
00086   std::string tip_name,root_name,xml_string;
00087   int free_angle;
00088   double sd;
00089 
00090   EXPECT_TRUE(loadRobotModel(nh,robot_model,xml_string));
00091   nh.param<int>("free_angle",free_angle,2);
00092   nh.param<double>("search_discretization",sd,0.01);
00093 
00094   if (!nh.getParam("root_name", root_name)){
00095     ROS_ERROR("PR2IK: No root name found on parameter server");
00096   }
00097   if (!nh.getParam("tip_name", tip_name)){
00098     ROS_ERROR("PR2IK: No tip name found on parameter server");
00099   }
00100 
00101   pr2_arm_kinematics::PR2ArmIKSolver ik(robot_model,root_name,tip_name,sd,free_angle);
00102 
00103   KDL::Chain kdl_chain;
00104   EXPECT_TRUE(pr2_arm_kinematics::getKDLChain(xml_string,root_name,tip_name,kdl_chain));
00105 
00106   int num_tests = 10000;
00107   EXPECT_TRUE(ik.active_);
00108 
00109   KDL::ChainFkSolverPos_recursive *jnt_to_pose_solver;
00110   KDL::JntArray jnt_pos_in;
00111   KDL::JntArray jnt_pos_out;
00112   KDL::Frame p_out;
00113   KDL::Frame p_ik;
00114 
00115   srand ( time(NULL) ); // initialize random seed:
00116 
00117   jnt_to_pose_solver = new KDL::ChainFkSolverPos_recursive(kdl_chain);
00118   jnt_pos_in.resize(7);
00119   jnt_pos_out.resize(7);
00120 
00121   kinematics_msgs::KinematicSolverInfo chain_info;
00122   ik.getSolverInfo(chain_info);
00123 
00124   int num_solutions(0);
00125 
00126   for(int kk = 0; kk < num_tests; kk++)
00127   {
00128     for(int i=0; i < 7; i++)
00129     {
00130       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));
00131       EXPECT_TRUE((jnt_pos_in(i) <= chain_info.limits[i].max_position));
00132       EXPECT_TRUE((jnt_pos_in(i) >= chain_info.limits[i].min_position));
00133     }
00134 
00135     if(jnt_to_pose_solver->JntToCart(jnt_pos_in,p_out) >=0)
00136     {
00137       bool ik_valid = (ik.CartToJnt(jnt_pos_in,p_out,jnt_pos_out) >= 0);
00138       if(ik_valid)
00139       {
00140         num_solutions++;
00141         jnt_to_pose_solver->JntToCart(jnt_pos_out,p_ik);
00142         for(int j=0; j< 3; j++)
00143         {
00144           EXPECT_NEAR(p_ik.M(j,0),p_out.M(j,0),IK_NEAR);
00145           EXPECT_NEAR(p_ik.M(j,1),p_out.M(j,1),IK_NEAR);
00146           EXPECT_NEAR(p_ik.M(j,2),p_out.M(j,2),IK_NEAR);
00147           EXPECT_NEAR(p_ik.p(j),p_out.p(j),IK_NEAR_TRANSLATE);
00148         }
00149       }
00150     }
00151   }
00152 
00153   bool success = ((double)num_solutions)/((double) num_tests) > 0.99;
00154   ROS_INFO("Success rate is %f",((double)num_solutions)/((double) num_tests));
00155   EXPECT_TRUE(success);
00156   delete jnt_to_pose_solver;
00157 }
00158 
00159 
00160 TEST(PR2ArmIK, inverseKinematicsSearch)
00161 {
00162   ros::NodeHandle nh("/pr2_ik_regression_test");
00163   urdf::Model robot_model;
00164   std::string tip_name,root_name,xml_string;
00165   int free_angle;
00166   double sd;
00167 
00168   EXPECT_TRUE(loadRobotModel(nh,robot_model,xml_string));
00169   nh.param<int>("free_angle",free_angle,2);
00170   nh.param<double>("search_discretization",sd,0.001);
00171   if (!nh.getParam("root_name", root_name)){
00172     ROS_ERROR("PR2IK: No root name found on parameter server");
00173   }
00174   if (!nh.getParam("tip_name", tip_name)){
00175     ROS_ERROR("PR2IK: No tip name found on parameter server");
00176   }
00177 
00178 
00179   pr2_arm_kinematics::PR2ArmIKSolver ik(robot_model,root_name,tip_name,sd,free_angle);
00180 
00181   KDL::Chain kdl_chain;
00182   EXPECT_TRUE(pr2_arm_kinematics::getKDLChain(xml_string,root_name,tip_name,kdl_chain));
00183 
00184   kinematics_msgs::KinematicSolverInfo chain_info;
00185   ik.getSolverInfo(chain_info);
00186 
00187   int num_tests = 10000;
00188   KDL::ChainFkSolverPos_recursive *jnt_to_pose_solver;
00189   KDL::JntArray jnt_pos_in;
00190   KDL::JntArray jnt_pos_test;
00191   std::vector<KDL::JntArray> jnt_pos_out;
00192   KDL::Frame p_out;
00193   KDL::Frame p_ik;
00194 
00195   srand ( time(NULL) );
00196 
00197   jnt_to_pose_solver = new KDL::ChainFkSolverPos_recursive(kdl_chain);
00198   jnt_pos_in.resize(7);
00199   jnt_pos_test.resize(7);
00200 
00201   int num_solutions(0);
00202 
00203   for(int kk = 0; kk < num_tests; kk++)
00204   {
00205     ROS_INFO("Test: %d",kk);
00206     for(int i=0; i < 7; i++)
00207     {
00208       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));
00209       EXPECT_TRUE((jnt_pos_in(i) <= chain_info.limits[i].max_position));
00210       EXPECT_TRUE((jnt_pos_in(i) >= chain_info.limits[i].min_position));
00211     }
00212     for(int i=0; i < 7; i++)
00213     {
00214       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));
00215       EXPECT_TRUE((jnt_pos_test(i) <= chain_info.limits[i].max_position));
00216       EXPECT_TRUE((jnt_pos_test(i) >= chain_info.limits[i].min_position));
00217       }
00218     if(jnt_to_pose_solver->JntToCart(jnt_pos_in,p_out) >=0)
00219     {
00220       moveit_msgs::MoveItErrorCodes error_code;
00221       bool ik_valid = (ik.CartToJntSearch(jnt_pos_test,p_out,jnt_pos_out,10) >= 0);
00222       if(ik_valid)
00223       {
00224         num_solutions++;
00225         for(int k=0; k < (int)jnt_pos_out.size(); k++)
00226         {
00227           jnt_to_pose_solver->JntToCart(jnt_pos_out[k],p_ik);
00228           for(int j=0; j< 3; j++)
00229           {
00230             EXPECT_NEAR(p_ik.M(j,0),p_out.M(j,0),IK_NEAR);
00231             EXPECT_NEAR(p_ik.M(j,1),p_out.M(j,1),IK_NEAR);
00232             EXPECT_NEAR(p_ik.M(j,2),p_out.M(j,2),IK_NEAR);
00233             EXPECT_NEAR(p_ik.p(j),p_out.p(j),IK_NEAR_TRANSLATE);
00234           }
00235         }
00236       }
00237       else
00238       {
00239         ROS_INFO("Failed solution");
00240         for(int m=0; m < 3; m++)
00241         {
00242           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));
00243         }
00244         printf("\n");
00245         ROS_INFO("Original joint values");
00246           for(int n = 0; n< 7; n++)
00247           {
00248             printf("%f ",jnt_pos_in(n));
00249           }
00250           printf("\n");
00251           ROS_INFO("Guess: %f",jnt_pos_test(2));
00252         ROS_INFO("\n\n\n");
00253       }
00254     }
00255   }
00256   bool success = ((double)num_solutions)/((double) num_tests) > 0.99;
00257   ROS_INFO("Success rate is %f",((double)num_solutions)/((double) num_tests));
00258   EXPECT_TRUE(success);
00259   delete jnt_to_pose_solver;
00260 }
00261 
00262 
00263 int main(int argc, char **argv)
00264 {
00265   testing::InitGoogleTest(&argc, argv);
00266   ros::init (argc, argv, "pr2_ik_regression_test");
00267   return RUN_ALL_TESTS();
00268 }


pr2_arm_ik_tests
Author(s): Sachin Chitta
autogenerated on Mon Sep 14 2015 14:18:15