Go to the documentation of this file.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_constraint_aware/kinematics_constraint_aware.h>
00043 #include <moveit/robot_model/robot_model.h>
00044 #include <moveit/robot_state/robot_state.h>
00045 #include <moveit/robot_state/joint_state_group.h>
00046 #include <moveit/planning_scene/planning_scene.h>
00047 #include <moveit/rdf_loader/rdf_loader.h>
00048 #include <moveit/robot_model_loader/robot_model_loader.h>
00049 #include <eigen_conversions/eigen_msg.h>
00050 #include <urdf/model.h>
00051 #include <srdfdom/model.h>
00052
00053 TEST(ConstraintAwareKinematics, getIK)
00054 {
00055 std::string group_name = "right_arm";
00056 std::string ik_link_name = "r_wrist_roll_link";
00057
00058 ROS_INFO("Initializing IK solver");
00059 planning_scene::PlanningScenePtr planning_scene;
00060 robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
00061 robot_model::RobotModelPtr kinematic_model = robot_model_loader.getModel();
00062
00063 const boost::shared_ptr<srdf::Model> &srdf = robot_model_loader.getSRDF();
00064 const boost::shared_ptr<urdf::ModelInterface>& urdf_model = robot_model_loader.getURDF();
00065
00066 planning_scene.reset(new planning_scene::PlanningScene(kinematic_model));
00067
00068 const robot_model::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(group_name);
00069
00070 robot_state::RobotStatePtr kinematic_state(new robot_state::RobotState(kinematic_model));
00071 robot_state::JointStateGroup* joint_state_group = kinematic_state->getJointStateGroup(group_name);
00072 kinematic_state->setToDefaultValues();
00073
00074 kinematics_constraint_aware::KinematicsConstraintAware solver(kinematic_model, "right_arm");
00075
00076 ros::NodeHandle nh("~");
00077 int number_ik_tests;
00078 nh.param("number_ik_tests", number_ik_tests, 1);
00079
00080 int acceptable_success_percentage;
00081 nh.param("accepatable_success_percentage", acceptable_success_percentage, 95);
00082
00083 unsigned int num_success = 0;
00084
00085 kinematics_constraint_aware::KinematicsRequest kinematics_request;
00086 kinematics_constraint_aware::KinematicsResponse kinematics_response;
00087 kinematics_response.solution_.reset(new robot_state::RobotState(planning_scene->getCurrentState()));
00088
00089 kinematics_request.group_name_ = group_name;
00090 kinematics_request.timeout_ = ros::Duration(5.0);
00091 kinematics_request.check_for_collisions_ = false;
00092 kinematics_request.robot_state_ = kinematic_state;
00093
00094 geometry_msgs::PoseStamped goal;
00095 goal.header.frame_id = kinematic_model->getModelFrame();
00096
00097 for(std::size_t i = 0; i < (unsigned int) number_ik_tests; ++i)
00098 {
00099 joint_state_group->setToRandomValues();
00100 const Eigen::Affine3d &end_effector_state = joint_state_group->getRobotState()->getLinkState(ik_link_name)->getGlobalLinkTransform();
00101 Eigen::Quaterniond quat(end_effector_state.rotation());
00102 Eigen::Vector3d point(end_effector_state.translation());
00103 goal.pose.position.x = point.x();
00104 goal.pose.position.y = point.y();
00105 goal.pose.position.z = point.z();
00106 goal.pose.orientation.x = quat.x();
00107 goal.pose.orientation.y = quat.y();
00108 goal.pose.orientation.z = quat.z();
00109 goal.pose.orientation.w = quat.w();
00110
00111 joint_state_group->setToRandomValues();
00112 kinematics_request.pose_stamped_vector_.clear();
00113 kinematics_request.pose_stamped_vector_.push_back(goal);
00114 ros::WallTime start = ros::WallTime::now();
00115 if(solver.getIK(planning_scene, kinematics_request, kinematics_response))
00116 num_success++;
00117 else
00118 printf("Failed in %f\n", (ros::WallTime::now()-start).toSec());
00119 }
00120 bool test_success = (((double)num_success)/number_ik_tests > acceptable_success_percentage/100.0);
00121 printf("success ratio: %d of %d", num_success, number_ik_tests);
00122 EXPECT_TRUE(test_success);
00123 }
00124
00125
00126 int main(int argc, char **argv)
00127 {
00128 testing::InitGoogleTest(&argc, argv);
00129 ros::init (argc, argv, "right_arm_kinematics");
00130 return RUN_ALL_TESTS();
00131 }