00001 #include <ros/ros.h>
00002 #include <pluginlib/class_loader.h>
00003 #include <kinematics_base/kinematics_base.h>
00004 #include <gtest/gtest.h>
00005
00006
00007 class MyTest
00008 {
00009 public:
00010 bool initialize()
00011 {
00012 ros::NodeHandle rh;
00013 pluginlib::ClassLoader<kinematics::KinematicsBase> kinematics_loader("kinematics_base", "kinematics::KinematicsBase");
00014 kinematics_solver = NULL;
00015 try{
00016 kinematics_solver = kinematics_loader.createClassInstance("pr2_arm_kinematics/PR2ArmKinematicsPlugin");
00017 }
00018 catch(pluginlib::PluginlibException& ex){
00019
00020 ROS_ERROR("The plugin failed to load. Error: %s", ex.what());
00021 return false;
00022 }
00023 if(kinematics_solver->initialize("right_arm"))
00024 return true;
00025 else
00026 return false;
00027 };
00028
00029 void pose_callback(const geometry_msgs::Pose &ik_pose,
00030 const std::vector<double> &joint_state,
00031 int &error_code)
00032 {
00033 std::vector<std::string> link_names;
00034 link_names.push_back("r_elbow_flex_link");
00035 std::vector<geometry_msgs::Pose> solutions;
00036 kinematics_solver->getPositionFK(link_names,joint_state,solutions);
00037 if(solutions[0].position.z > 0.0)
00038 error_code = 1;
00039 else
00040 error_code = -1;
00041 };
00042
00043 void joint_state_callback(const geometry_msgs::Pose &ik_pose,
00044 const std::vector<double> &joint_state,
00045 int &error_code)
00046 {
00047 error_code = 1;
00048 };
00049 kinematics::KinematicsBase* kinematics_solver;
00050 };
00051
00052 TEST(PR2ArmIKPlugin, testplugin)
00053 {
00054 MyTest my_test;
00055 ASSERT_TRUE(my_test.initialize());
00056
00057 std::string root_name = my_test.kinematics_solver->getBaseFrame();
00058 EXPECT_TRUE(root_name == std::string("torso_lift_link"));
00059 std::string tool_name = my_test.kinematics_solver->getToolFrame();
00060 EXPECT_TRUE(tool_name == std::string("r_wrist_roll_link"));
00061 std::vector<std::string> joint_names = my_test.kinematics_solver->getJointNames();
00062 EXPECT_EQ((int)joint_names.size(),7);
00063
00064 EXPECT_EQ(joint_names[0],"r_shoulder_pan_joint");
00065 EXPECT_EQ(joint_names[1],"r_shoulder_lift_joint");
00066 EXPECT_EQ(joint_names[2],"r_upper_arm_roll_joint");
00067 EXPECT_EQ(joint_names[3],"r_elbow_flex_joint");
00068 EXPECT_EQ(joint_names[4],"r_forearm_roll_joint");
00069 EXPECT_EQ(joint_names[5],"r_wrist_flex_joint");
00070 EXPECT_EQ(joint_names[6],"r_wrist_roll_joint");
00071
00072
00073 geometry_msgs::Pose pose;
00074 pose.position.x = 0.75;
00075 pose.position.y = -0.188;
00076 pose.position.z = 0.0;
00077 pose.orientation.x = 0.0;
00078 pose.orientation.y = 0.0;
00079 pose.orientation.z = 0.0;
00080 pose.orientation.w = 1.0;
00081 std::vector<double> seed,solution;
00082 seed.resize(7,0.0);
00083 double timeout = 5.0;
00084 int error_code;
00085 bool result = my_test.kinematics_solver->searchPositionIK(pose,seed,timeout,solution,error_code);
00086 EXPECT_TRUE(result);
00087 result = my_test.kinematics_solver->getPositionIK(pose,solution,solution,error_code);
00088 EXPECT_TRUE(result);
00089
00090 result = my_test.kinematics_solver->searchPositionIK(pose,seed,timeout,solution,
00091 boost::bind(&MyTest::pose_callback, &my_test, _1, _2, _3),
00092 boost::bind(&MyTest::joint_state_callback, &my_test, _1, _2, _3),
00093 error_code);
00094 EXPECT_TRUE(result);
00095 }
00096
00097 int main(int argc, char **argv){
00098 testing::InitGoogleTest(&argc, argv);
00099 ros::init (argc, argv, "pr2_right_arm_ik_test");
00100 return RUN_ALL_TESTS();
00101 }