test_kinematics_as_plugin.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2008, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of Willow Garage, Inc. nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Sachin Chitta
00036 *********************************************************************/
00037 
00038 #include <ros/ros.h>
00039 #include <gtest/gtest.h>
00040 #include <pluginlib/class_loader.h>
00041 
00042 // MoveIt!
00043 #include <moveit/kinematics_base/kinematics_base.h>
00044 #include <moveit/robot_model/robot_model.h>
00045 #include <moveit/robot_state/robot_state.h>
00046 #include <moveit/rdf_loader/rdf_loader.h>
00047 #include <urdf/model.h>
00048 #include <srdfdom/model.h>
00049 
00050 #define IK_NEAR 1e-4
00051 #define IK_NEAR_TRANSLATE 1e-5
00052 
00053 class MyTest
00054 {
00055  public:
00056   bool initialize()
00057   {
00058     double search_discretization;
00059     ros::NodeHandle nh("~");
00060     kinematics_solver = NULL;
00061     kinematics_loader.reset(new pluginlib::ClassLoader<kinematics::KinematicsBase>("moveit_core", "kinematics::KinematicsBase"));
00062     std::string plugin_name;
00063     if (!nh.getParam("plugin_name", plugin_name))
00064     {
00065       ROS_ERROR("No plugin name found on parameter server");
00066       EXPECT_TRUE(0);
00067       return false;
00068     }
00069     ROS_INFO("Plugin name: %s",plugin_name.c_str());
00070     try
00071     {
00072       kinematics_solver = kinematics_loader->createClassInstance(plugin_name);
00073     }
00074     catch(pluginlib::PluginlibException& ex)//handle the class failing to load
00075     {
00076       ROS_ERROR("The plugin failed to load. Error: %s", ex.what());
00077       EXPECT_TRUE(0);
00078       return false;
00079     }
00080     std::string root_name, tip_name;
00081     ros::WallTime start_time = ros::WallTime::now();
00082     bool done = true;
00083     while((ros::WallTime::now()-start_time).toSec() <= 5.0)
00084     {
00085       if (!nh.getParam("root_name", root_name))
00086       {
00087         ROS_ERROR("No root name found on parameter server");
00088         done = false;
00089         EXPECT_TRUE(0);
00090         continue;
00091       }
00092       if (!nh.getParam("tip_name", tip_name))
00093       {
00094         ROS_ERROR("No tip name found on parameter server");
00095         done = false;
00096         EXPECT_TRUE(0);
00097         continue;
00098       }
00099       if (!nh.getParam("search_discretization", search_discretization))
00100       {
00101         ROS_ERROR("No search discretization found on parameter server");
00102         done = false;
00103         EXPECT_TRUE(0);
00104         continue;
00105       }
00106       done = true;
00107     }
00108 
00109     if(!done)
00110       return false;
00111 
00112     if(kinematics_solver->initialize("robot_description","right_arm",root_name,tip_name,search_discretization))
00113       return true;
00114     else
00115     {
00116       EXPECT_TRUE(0);
00117       return false;
00118     }
00119 
00120   };
00121 
00122   void joint_state_callback(const geometry_msgs::Pose &ik_pose,
00123                             const std::vector<double> &joint_state,
00124                             moveit_msgs::MoveItErrorCodes &error_code)
00125   {
00126     std::vector<std::string> link_names;
00127     link_names.push_back("r_elbow_flex_link");
00128     std::vector<geometry_msgs::Pose> solutions;
00129     solutions.resize(1);
00130     if(!kinematics_solver->getPositionFK(link_names,joint_state,solutions))
00131       error_code.val = error_code.PLANNING_FAILED;
00132     if(solutions[0].position.z > 0.0)
00133       error_code.val = error_code.SUCCESS;
00134     else
00135       error_code.val = error_code.PLANNING_FAILED;
00136   };
00137   kinematics::KinematicsBase* kinematics_solver;
00138   boost::shared_ptr<pluginlib::ClassLoader<kinematics::KinematicsBase> > kinematics_loader;
00139 };
00140 
00141 MyTest my_test;
00142 
00143 TEST(ArmIKPlugin, initialize)
00144 {
00145   ASSERT_TRUE(my_test.initialize());
00146   // Test getting chain information
00147   std::string root_name = my_test.kinematics_solver->getBaseFrame();
00148   EXPECT_TRUE(root_name == std::string("torso_lift_link"));
00149   std::string tool_name = my_test.kinematics_solver->getTipFrame();
00150   EXPECT_TRUE(tool_name == std::string("r_wrist_roll_link"));
00151   std::vector<std::string> joint_names = my_test.kinematics_solver->getJointNames();
00152   EXPECT_EQ((int)joint_names.size(), 7);
00153 
00154   EXPECT_EQ(joint_names[0], "r_shoulder_pan_joint");
00155   EXPECT_EQ(joint_names[1], "r_shoulder_lift_joint");
00156   EXPECT_EQ(joint_names[2], "r_upper_arm_roll_joint");
00157   EXPECT_EQ(joint_names[3], "r_elbow_flex_joint");
00158   EXPECT_EQ(joint_names[4], "r_forearm_roll_joint");
00159   EXPECT_EQ(joint_names[5], "r_wrist_flex_joint");
00160   EXPECT_EQ(joint_names[6], "r_wrist_roll_joint");
00161 }
00162 
00163 TEST(ArmIKPlugin, getFK)
00164 {
00165   rdf_loader::RDFLoader rdf_loader_;
00166   robot_model::RobotModelPtr kinematic_model;
00167   const boost::shared_ptr<srdf::Model> &srdf = rdf_loader_.getSRDF();
00168   const boost::shared_ptr<urdf::ModelInterface>& urdf_model = rdf_loader_.getURDF();
00169   kinematic_model.reset(new robot_model::RobotModel(urdf_model, srdf));
00170   robot_model::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(my_test.kinematics_solver->getGroupName());
00171 
00172   std::vector<double> seed, fk_values, solution;
00173   moveit_msgs::MoveItErrorCodes error_code;
00174   solution.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00175 
00176   std::vector<std::string> fk_names;
00177   fk_names.push_back(my_test.kinematics_solver->getTipFrame());
00178 
00179   robot_state::RobotState kinematic_state(kinematic_model);
00180   robot_state::JointStateGroup* joint_state_group = kinematic_state.getJointStateGroup(my_test.kinematics_solver->getGroupName());
00181 
00182   ros::NodeHandle nh("~");
00183   int number_fk_tests;
00184   nh.param("number_fk_tests", number_fk_tests, 100);
00185 
00186   for(unsigned int i=0; i < (unsigned int) number_fk_tests; ++i)
00187   {
00188     seed.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00189     fk_values.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00190 
00191     joint_state_group->setToRandomValues();
00192     joint_state_group->getVariableValues(fk_values);
00193 
00194     std::vector<geometry_msgs::Pose> poses;
00195     poses.resize(1);
00196     bool result_fk = my_test.kinematics_solver->getPositionFK(fk_names, fk_values, poses);
00197     ASSERT_TRUE(result_fk);
00198   }
00199 }
00200 
00201 TEST(ArmIKPlugin, searchIK)
00202 {
00203   rdf_loader::RDFLoader rdf_loader_;
00204   robot_model::RobotModelPtr kinematic_model;
00205   const boost::shared_ptr<srdf::Model> &srdf_model = rdf_loader_.getSRDF();
00206   const boost::shared_ptr<urdf::ModelInterface>& urdf_model = rdf_loader_.getURDF();
00207   kinematic_model.reset(new robot_model::RobotModel(urdf_model, srdf_model));
00208   robot_model::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(my_test.kinematics_solver->getGroupName());
00209 
00210   //Test inverse kinematics
00211   std::vector<double> seed, fk_values, solution;
00212   double timeout = 5.0;
00213   moveit_msgs::MoveItErrorCodes error_code;
00214   solution.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00215 
00216   std::vector<std::string> fk_names;
00217   fk_names.push_back(my_test.kinematics_solver->getTipFrame());
00218 
00219   robot_state::RobotState kinematic_state(kinematic_model);
00220   robot_state::JointStateGroup* joint_state_group = kinematic_state.getJointStateGroup(my_test.kinematics_solver->getGroupName());
00221 
00222   ros::NodeHandle nh("~");
00223   int number_ik_tests;
00224   nh.param("number_ik_tests", number_ik_tests, 10);
00225   unsigned int success = 0;
00226 
00227   ros::WallTime start_time = ros::WallTime::now();
00228   for(unsigned int i=0; i < (unsigned int) number_ik_tests; ++i)
00229   {
00230     seed.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00231     fk_values.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00232 
00233     joint_state_group->setToRandomValues();
00234     joint_state_group->getVariableValues(fk_values);
00235 
00236     std::vector<geometry_msgs::Pose> poses;
00237     poses.resize(1);
00238     bool result_fk = my_test.kinematics_solver->getPositionFK(fk_names, fk_values, poses);
00239     ASSERT_TRUE(result_fk);
00240 
00241     bool result = my_test.kinematics_solver->searchPositionIK(poses[0], seed, timeout, solution, error_code);
00242     ROS_DEBUG("Pose: %f %f %f",poses[0].position.x, poses[0].position.y, poses[0].position.z);
00243     ROS_DEBUG("Orient: %f %f %f %f",poses[0].orientation.x, poses[0].orientation.y, poses[0].orientation.z, poses[0].orientation.w);
00244     if(result)
00245     {
00246       success++;
00247       result = my_test.kinematics_solver->getPositionIK(poses[0], solution, solution, error_code);
00248       EXPECT_TRUE(result);
00249     }
00250 
00251     std::vector<geometry_msgs::Pose> new_poses;
00252     new_poses.resize(1);
00253     result_fk = my_test.kinematics_solver->getPositionFK(fk_names, solution, new_poses);
00254 
00255     EXPECT_NEAR(poses[0].position.x, new_poses[0].position.x, IK_NEAR);
00256     EXPECT_NEAR(poses[0].position.y, new_poses[0].position.y, IK_NEAR);
00257     EXPECT_NEAR(poses[0].position.z, new_poses[0].position.z, IK_NEAR);
00258 
00259     EXPECT_NEAR(poses[0].orientation.x, new_poses[0].orientation.x, IK_NEAR);
00260     EXPECT_NEAR(poses[0].orientation.y, new_poses[0].orientation.y, IK_NEAR);
00261     EXPECT_NEAR(poses[0].orientation.z, new_poses[0].orientation.z, IK_NEAR);
00262     EXPECT_NEAR(poses[0].orientation.w, new_poses[0].orientation.w, IK_NEAR);
00263   }
00264   ROS_INFO("Success Rate: %f",(double)success/number_ik_tests);
00265   bool success_count = (success > 0.99 * number_ik_tests);
00266   EXPECT_TRUE(success_count);
00267   ROS_INFO("Elapsed time: %f", (ros::WallTime::now()-start_time).toSec());
00268 }
00269 
00270 TEST(ArmIKPlugin, searchIKWithCallbacks)
00271 {
00272   rdf_loader::RDFLoader rdf_loader_;
00273   robot_model::RobotModelPtr kinematic_model;
00274   const boost::shared_ptr<srdf::Model> &srdf = rdf_loader_.getSRDF();
00275   const boost::shared_ptr<urdf::ModelInterface>& urdf_model = rdf_loader_.getURDF();
00276   kinematic_model.reset(new robot_model::RobotModel(urdf_model, srdf));
00277   robot_model::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(my_test.kinematics_solver->getGroupName());
00278 
00279   //Test inverse kinematics
00280   std::vector<double> seed,fk_values,solution;
00281   double timeout = 5.0;
00282   moveit_msgs::MoveItErrorCodes error_code;
00283   solution.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00284 
00285   std::vector<std::string> fk_names;
00286   fk_names.push_back(my_test.kinematics_solver->getTipFrame());
00287 
00288   robot_state::RobotState kinematic_state(kinematic_model);
00289   robot_state::JointStateGroup* joint_state_group = kinematic_state.getJointStateGroup(my_test.kinematics_solver->getGroupName());
00290 
00291   ros::NodeHandle nh("~");
00292   int number_ik_tests;
00293   nh.param("number_ik_tests_with_callbacks", number_ik_tests, 10);
00294   unsigned int success = 0;
00295   unsigned int num_actual_tests = 0;
00296 
00297   for(unsigned int i=0; i < (unsigned int) number_ik_tests; ++i)
00298   {
00299     seed.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00300     fk_values.resize(my_test.kinematics_solver->getJointNames().size(), 0.0);
00301 
00302     joint_state_group->setToRandomValues();
00303     joint_state_group->getVariableValues(fk_values);
00304 
00305     std::vector<geometry_msgs::Pose> poses;
00306     poses.resize(1);
00307     bool result_fk = my_test.kinematics_solver->getPositionFK(fk_names, fk_values, poses);
00308     ASSERT_TRUE(result_fk);
00309     if(poses[0].position.z < 0.0)
00310       continue;
00311 
00312     num_actual_tests++;
00313     bool result = my_test.kinematics_solver->searchPositionIK(poses[0], seed, timeout, solution,
00314                                                               boost::bind(&MyTest::joint_state_callback, &my_test, _1, _2, _3), error_code);
00315 
00316     if(result)
00317     {
00318       success++;
00319       std::vector<geometry_msgs::Pose> new_poses;
00320       new_poses.resize(1);
00321       result_fk = my_test.kinematics_solver->getPositionFK(fk_names, solution, new_poses);
00322 
00323       EXPECT_NEAR(poses[0].position.x, new_poses[0].position.x, IK_NEAR);
00324       EXPECT_NEAR(poses[0].position.y, new_poses[0].position.y, IK_NEAR);
00325       EXPECT_NEAR(poses[0].position.z, new_poses[0].position.z, IK_NEAR);
00326 
00327       EXPECT_NEAR(poses[0].orientation.x, new_poses[0].orientation.x, IK_NEAR);
00328       EXPECT_NEAR(poses[0].orientation.y, new_poses[0].orientation.y, IK_NEAR);
00329       EXPECT_NEAR(poses[0].orientation.z, new_poses[0].orientation.z, IK_NEAR);
00330       EXPECT_NEAR(poses[0].orientation.w, new_poses[0].orientation.w, IK_NEAR);
00331     }
00332 
00333     if(!ros::ok())
00334       break;
00335   }
00336   ROS_INFO("Success with callbacks (%%): %f",(double)success/num_actual_tests*100.0);
00337 }
00338 
00339 
00340 int main(int argc, char **argv)
00341 {
00342   testing::InitGoogleTest(&argc, argv);
00343   ros::init (argc, argv, "right_arm_kinematics");
00344   return RUN_ALL_TESTS();
00345 }


pr2_moveit_tests
Author(s):
autogenerated on Mon Oct 6 2014 11:13:32