test_kinematics_as_plugin.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 <ros/ros.h>
00038 #include <gtest/gtest.h>
00039 #include <pluginlib/class_loader.h>
00040 
00041 #include <kinematics_base/kinematics_base.h>
00042 
00043 // MoveIt!
00044 #include <robot_model/robot_model.h>
00045 #include <robot_state/robot_state.h>
00046 #include <rdf_loader/rdf_loader.h>
00047 #include <urdf_interface/model.h>
00048 #include <urdf/model.h>
00049 #include <srdf/model.h>
00050 
00051 #define IK_NEAR 1e-4
00052 #define IK_NEAR_TRANSLATE 1e-5
00053 
00054 class MyTest
00055 {
00056  public:
00057   bool initialize()
00058   {
00059     double search_discretization;
00060     ros::NodeHandle nh("~");
00061     kinematics_solver = NULL;
00062     kinematics_loader.reset(new pluginlib::ClassLoader<kinematics::KinematicsBase>("kinematics_base", "kinematics::KinematicsBase"));
00063     std::string plugin_name;
00064     if (!nh.getParam("plugin_name", plugin_name))
00065     {
00066       ROS_ERROR("No plugin name found on parameter server");
00067       EXPECT_TRUE(0);
00068       return false;
00069     }
00070     ROS_INFO("Plugin name: %s",plugin_name.c_str());
00071     try
00072     {
00073       kinematics_solver = kinematics_loader->createClassInstance(plugin_name);
00074     }
00075     catch(pluginlib::PluginlibException& ex)//handle the class failing to load
00076     {
00077       ROS_ERROR("The plugin failed to load. Error: %s", ex.what());
00078       EXPECT_TRUE(0);
00079       return false;
00080     }
00081     std::string root_name, tip_name;
00082     ros::WallTime start_time = ros::WallTime::now();
00083     bool done = true;
00084     while((ros::WallTime::now()-start_time).toSec() <= 5.0)
00085     {
00086       if (!nh.getParam("root_name", root_name))
00087       {
00088         ROS_ERROR("No root name found on parameter server");
00089         done = false;
00090         EXPECT_TRUE(0);
00091         continue;
00092       }
00093       if (!nh.getParam("tip_name", tip_name))
00094       {
00095         ROS_ERROR("No tip name found on parameter server");
00096         done = false;
00097         EXPECT_TRUE(0);
00098         continue;
00099       }
00100       if (!nh.getParam("search_discretization", search_discretization))
00101       {
00102         ROS_ERROR("No search discretization found on parameter server");
00103         done = false;
00104         EXPECT_TRUE(0);
00105         continue;
00106       }
00107       done = true;
00108     }
00109 
00110     if(!done)
00111       return false;
00112 
00113     if(kinematics_solver->initialize("right_arm",root_name,tip_name,search_discretization))
00114       return true;
00115     else
00116     {
00117       EXPECT_TRUE(0);
00118       return false;
00119     }
00120 
00121   };
00122 
00123   void pose_callback(const geometry_msgs::Pose &ik_pose,
00124                      const std::vector<double> &joint_state,
00125                      moveit_msgs::MoveItErrorCodes &error_code)
00126   {
00127     error_code.val = error_code.SUCCESS;
00128   };
00129 
00130   void joint_state_callback(const geometry_msgs::Pose &ik_pose,
00131                             const std::vector<double> &joint_state,
00132                             moveit_msgs::MoveItErrorCodes &error_code)
00133   {
00134     std::vector<std::string> link_names;
00135     link_names.push_back("r_elbow_flex_link");
00136     std::vector<geometry_msgs::Pose> solutions;
00137     solutions.resize(1);
00138     if(!kinematics_solver->getPositionFK(link_names,joint_state,solutions))
00139       error_code.val = error_code.PLANNING_FAILED;
00140     if(solutions[0].position.z > 0.0)
00141       error_code.val = error_code.SUCCESS;
00142     else
00143       error_code.val = error_code.PLANNING_FAILED;
00144   };
00145   kinematics::KinematicsBase* kinematics_solver;
00146   boost::shared_ptr<pluginlib::ClassLoader<kinematics::KinematicsBase> > kinematics_loader;
00147 };
00148 
00149 MyTest my_test;
00150 
00151 TEST(ArmIKPlugin, initialize)
00152 {
00153   ASSERT_TRUE(my_test.initialize());
00154   // Test getting chain information
00155   std::string root_name = my_test.kinematics_solver->getBaseFrame();
00156   EXPECT_TRUE(root_name == std::string("torso_lift_link"));
00157   std::string tool_name = my_test.kinematics_solver->getTipFrame();
00158   EXPECT_TRUE(tool_name == std::string("r_wrist_roll_link"));
00159   std::vector<std::string> joint_names = my_test.kinematics_solver->getJointNames();
00160   EXPECT_EQ((int)joint_names.size(), 7);
00161 
00162   EXPECT_EQ(joint_names[0], "r_shoulder_pan_joint");
00163   EXPECT_EQ(joint_names[1], "r_shoulder_lift_joint");
00164   EXPECT_EQ(joint_names[2], "r_upper_arm_roll_joint");
00165   EXPECT_EQ(joint_names[3], "r_elbow_flex_joint");
00166   EXPECT_EQ(joint_names[4], "r_forearm_roll_joint");
00167   EXPECT_EQ(joint_names[5], "r_wrist_flex_joint");
00168   EXPECT_EQ(joint_names[6], "r_wrist_roll_joint");
00169 }
00170 
00171 TEST(ArmIKPlugin, getFK)
00172 {
00173   rdf_loader::RDFLoader rdf_loader_;
00174   robot_model::RobotModelPtr kinematic_model;
00175   const boost::shared_ptr<srdf::Model> &srdf = rdf_loader_.getSRDF();
00176   const boost::shared_ptr<urdf::ModelInterface>& urdf_model = rdf_loader_.getURDF();
00177   robot_model.reset(new robot_model::RobotModel(urdf_model, srdf));
00178   robot_model::RobotModel::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(my_test.kinematics_solver->getGroupName());
00179 
00180   std::vector<double> seed, fk_values, solution;
00181   moveit_msgs::MoveItErrorCodes error_code;
00182   solution.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00183 
00184   std::vector<std::string> fk_names;
00185   fk_names.push_back(my_test.kinematics_solver->getTipFrame());
00186 
00187   robot_model::RobotState *kinematic_state(kinematic_model);
00188   robot_state::RobotState::JointStateGroup joint_state_group(&kinematic_state,
00189                                                                      (const planning_models::RobotModel::JointModelGroup*) joint_model_group);
00190 
00191   ros::NodeHandle nh("~");
00192   unsigned int number_fk_tests;
00193   nh.param("number_fk_tests", number_fk_tests, 100);
00194 
00195   for(unsigned int i=0; i < number_fk_tests; ++i)
00196   {
00197     seed.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00198     fk_values.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00199 
00200     joint_state_group.setToRandomValues();
00201     joint_state_group.getGroupStateValues(fk_values);
00202 
00203     std::vector<geometry_msgs::Pose> poses;
00204     poses.resize(1);
00205     bool result_fk = my_test.kinematics_solver->getPositionFK(fk_names, fk_values, poses);
00206     ASSERT_TRUE(result_fk);
00207   }
00208 }
00209 
00210 TEST(ArmIKPlugin, searchIK)
00211 {
00212   rdf_loader::RDFLoader rdf_loader_;
00213   robot_model::RobotModelPtr kinematic_model;
00214   const boost::shared_ptr<srdf::Model> &srdf_model = rdf_loader_.getSRDF();
00215   const boost::shared_ptr<urdf::ModelInterface>& urdf_model = rdf_loader_.getURDF();
00216   robot_model.reset(new planning_models::RobotModel(urdf_model, srdf));
00217   planning_models::RobotModel::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(my_test.kinematics_solver->getGroupName());
00218 
00219   //Test inverse kinematics
00220   std::vector<double> seed, fk_values, solution;
00221   double timeout = 5.0;
00222   moveit_msgs::MoveItErrorCodes error_code;
00223   solution.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00224 
00225   std::vector<std::string> fk_names;
00226   fk_names.push_back(my_test.kinematics_solver->getTipFrame());
00227 
00228   planning_models::RobotState *kinematic_state(kinematic_model);
00229   planning_models::RobotState *::JointStateGroup joint_state_group(&kinematic_state, (const planning_models::RobotModel::JointModelGroup*) joint_model_group);
00230 
00231   ros::NodeHandle nh("~");
00232   unsigned int number_ik_tests;
00233   nh.param("number_ik_tests", number_ik_tests, 10);
00234   unsigned int success = 0;
00235 
00236   ros::WallTime start_time = ros::WallTime::now();
00237   for(unsigned int i=0; i < number_ik_tests; ++i)
00238   {
00239     seed.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00240     fk_values.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00241 
00242     joint_state_group.setToRandomValues();
00243     joint_state_group.getGroupStateValues(fk_values);
00244 
00245     std::vector<geometry_msgs::Pose> poses;
00246     poses.resize(1);
00247     bool result_fk = my_test.kinematics_solver->getPositionFK(fk_names, fk_values, poses);
00248     ASSERT_TRUE(result_fk);
00249 
00250     bool result = my_test.kinematics_solver->searchPositionIK(poses[0], seed, timeout, solution, error_code);
00251     ROS_DEBUG("Pose: %f %f %f",poses[0].position.x, poses[0].position.y, poses[0].position.z);
00252     ROS_DEBUG("Orient: %f %f %f %f",poses[0].orientation.x, poses[0].orientation.y, poses[0].orientation.z, poses[0].orientation.w);
00253     if(result)
00254     {
00255       success++;
00256       result = my_test.kinematics_solver->getPositionIK(poses[0], solution, solution, error_code);
00257       EXPECT_TRUE(result);
00258     }
00259 
00260     std::vector<geometry_msgs::Pose> new_poses;
00261     new_poses.resize(1);
00262     result_fk = my_test.kinematics_solver->getPositionFK(fk_names, solution, new_poses);
00263 
00264     EXPECT_NEAR(poses[0].position.x, new_poses[0].position.x, IK_NEAR);
00265     EXPECT_NEAR(poses[0].position.y, new_poses[0].position.y, IK_NEAR);
00266     EXPECT_NEAR(poses[0].position.z, new_poses[0].position.z, IK_NEAR);
00267 
00268     EXPECT_NEAR(poses[0].orientation.x, new_poses[0].orientation.x, IK_NEAR);
00269     EXPECT_NEAR(poses[0].orientation.y, new_poses[0].orientation.y, IK_NEAR);
00270     EXPECT_NEAR(poses[0].orientation.z, new_poses[0].orientation.z, IK_NEAR);
00271     EXPECT_NEAR(poses[0].orientation.w, new_poses[0].orientation.w, IK_NEAR);
00272   }
00273   ROS_INFO("Success Rate: %f",(double)success/total_tests);
00274   bool success_count = (success > 0.99*total_tests);
00275   EXPECT_TRUE(success_count);
00276   ROS_INFO("Elapsed time: %f", (ros::WallTime::now()-start_time).toSec());
00277   sleep(5.0);
00278 }
00279 
00280 TEST(ArmIKPlugin, searchIKWithCallbacks)
00281 {
00282   rdf_loader::RDFLoader rdf_loader_;
00283   planning_models::RobotModelPtr kinematic_model;
00284   const boost::shared_ptr<srdf::Model> &srdf = rdf_loader_.getSRDF();
00285   const boost::shared_ptr<urdf::ModelInterface>& urdf_model = rdf_loader_.getURDF();
00286   robot_model.reset(new planning_models::RobotModel(urdf_model, srdf));
00287   planning_models::RobotModel::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(my_test.kinematics_solver->getGroupName());
00288 
00289   //Test inverse kinematics
00290   std::vector<double> seed,fk_values,solution;
00291   double timeout = 5.0;
00292   moveit_msgs::MoveItErrorCodes error_code;
00293   solution.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00294 
00295   std::vector<std::string> fk_names;
00296   fk_names.push_back(my_test.kinematics_solver->getTipFrame());
00297 
00298   planning_models::RobotState *kinematic_state(kinematic_model);
00299   planning_models::RobotState *::JointStateGroup joint_state_group(&kinematic_state,
00300                                                                      (const planning_models::RobotModel::JointModelGroup*) joint_model_group);
00301 
00302   unsigned int num_tests = 0;
00303   unsigned int success = 0;
00304 
00305   ros::NodeHandle nh("~");
00306   unsigned int number_ik_tests;
00307   nh.param("number_ik_tests_with_callbacks", number_ik_tests, 10);
00308   unsigned int success = 0;
00309 
00310   for(unsigned int i=0; i < number_ik_tests; ++i)
00311   {
00312     seed.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00313     fk_values.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00314 
00315     joint_state_group.setToRandomValues();
00316     joint_state_group.getGroupStateValues(fk_values);
00317 
00318     std::vector<geometry_msgs::Pose> poses;
00319     poses.resize(1);
00320     bool result_fk = my_test.kinematics_solver->getPositionFK(fk_names, fk_values, poses);
00321     ASSERT_TRUE(result_fk);
00322     if(poses[0].position.z < 0.0)
00323       continue;
00324 
00325     num_tests++;
00326     bool result = my_test.kinematics_solver->searchPositionIK(poses[0], seed, timeout, solution,
00327                                                               boost::bind(&MyTest::pose_callback, &my_test, _1, _2, _3),
00328                                                               boost::bind(&MyTest::joint_state_callback, &my_test, _1, _2, _3), error_code);
00329 
00330     if(result)
00331     {
00332       success++;
00333       std::vector<geometry_msgs::Pose> new_poses;
00334       new_poses.resize(1);
00335       result_fk = my_test.kinematics_solver->getPositionFK(fk_names, solution, new_poses);
00336 
00337       EXPECT_NEAR(poses[0].position.x, new_poses[0].position.x, IK_NEAR);
00338       EXPECT_NEAR(poses[0].position.y, new_poses[0].position.y, IK_NEAR);
00339       EXPECT_NEAR(poses[0].position.z, new_poses[0].position.z, IK_NEAR);
00340 
00341       EXPECT_NEAR(poses[0].orientation.x, new_poses[0].orientation.x, IK_NEAR);
00342       EXPECT_NEAR(poses[0].orientation.y, new_poses[0].orientation.y, IK_NEAR);
00343       EXPECT_NEAR(poses[0].orientation.z, new_poses[0].orientation.z, IK_NEAR);
00344       EXPECT_NEAR(poses[0].orientation.w, new_poses[0].orientation.w, IK_NEAR);
00345     }
00346 
00347     if(!ros::ok())
00348       break;
00349   }
00350   ROS_INFO("Success with callbacks (%%): %f",(double)success/num_tests);
00351   bool success_count = (success > 0.5*num_tests);
00352   //  EXPECT_TRUE(success_count);
00353 }
00354 
00355 
00356 int main(int argc, char **argv)
00357 {
00358   testing::InitGoogleTest(&argc, argv);
00359   ros::init (argc, argv, "right_arm_kinematics");
00360   return RUN_ALL_TESTS();
00361 }


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