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


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