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