$search
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 the Willow Garage 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, Ioan Sucan 00036 *********************************************************************/ 00037 00038 #include <ros/ros.h> 00039 #include <arm_navigation_msgs/GetRobotState.h> 00040 #include <arm_navigation_msgs/GetJointTrajectoryValidity.h> 00041 #include <gtest/gtest.h> 00042 00043 00044 TEST(EnvironmentServer, AllowableContactsTest) 00045 { 00046 00047 ROS_INFO("Running test"); 00048 ros::NodeHandle rh; 00049 00050 ros::service::waitForService("/environment_server/get_trajectory_validity"); 00051 arm_navigation_msgs::GetJointTrajectoryValidity::Request req; 00052 arm_navigation_msgs::GetJointTrajectoryValidity::Response res; 00053 ros::ServiceClient check_trajectory_validity_client_ = rh.serviceClient<arm_navigation_msgs::GetJointTrajectoryValidity>("/environment_server/get_trajectory_validity"); 00054 00055 // ros::service::waitForService("/environment_server/get_robot_state"); 00056 ros::ServiceClient get_state_client_ = rh.serviceClient<arm_navigation_msgs::GetRobotState>("/environment_server/get_robot_state"); 00057 arm_navigation_msgs::GetRobotState::Request request; 00058 arm_navigation_msgs::GetRobotState::Response response; 00059 if(get_state_client_.call(request,response)) 00060 { 00061 req.robot_state = response.robot_state; 00062 } 00063 else 00064 { 00065 ROS_ERROR("Service call to get robot state failed on %s",get_state_client_.getService().c_str()); 00066 } 00067 00068 req.trajectory.joint_names.push_back("r_shoulder_pan_joint"); 00069 req.trajectory.points.resize(100); 00070 for(unsigned int i=0; i < 100; i++) 00071 { 00072 req.trajectory.points[i].positions.push_back((M_PI*i/15.0)/100.0); 00073 //req.trajectory.points[i].positions.push_back(0.0); 00074 } 00075 req.check_collisions = true; 00076 EXPECT_TRUE(check_trajectory_validity_client_.call(req,res)); 00077 if(!(res.error_code.val == res.error_code.SUCCESS)) 00078 { 00079 ROS_INFO("Collision detected without allowable contact region set"); 00080 } 00081 EXPECT_FALSE(res.error_code.val == res.error_code.SUCCESS); 00082 00083 sleep(2.0); 00084 req.allowed_contacts.resize(1); 00085 req.allowed_contacts[0].name = "table_region"; 00086 req.allowed_contacts[0].shape.type = arm_navigation_msgs::Shape::BOX; 00087 req.allowed_contacts[0].shape.dimensions.resize(3); 00088 00089 req.allowed_contacts[0].shape.dimensions[0]= 1.0; 00090 req.allowed_contacts[0].shape.dimensions[1]= 1.0; 00091 req.allowed_contacts[0].shape.dimensions[2]= 1.0; 00092 req.allowed_contacts[0].pose_stamped.header.frame_id = "torso_lift_link"; 00093 req.allowed_contacts[0].pose_stamped.header.stamp = ros::Time(0.0); 00094 00095 req.allowed_contacts[0].pose_stamped.pose.position.x = 1.0; 00096 req.allowed_contacts[0].pose_stamped.pose.position.y = 0.0; 00097 req.allowed_contacts[0].pose_stamped.pose.position.z = 0.0; 00098 00099 req.allowed_contacts[0].pose_stamped.pose.orientation.w = 1.0; 00100 req.allowed_contacts[0].link_names.push_back("r_shoulder_pan_link"); 00101 req.allowed_contacts[0].link_names.push_back("r_shoulder_lift_link"); 00102 req.allowed_contacts[0].link_names.push_back("r_upper_arm_link"); 00103 req.allowed_contacts[0].link_names.push_back("r_elbow_flex_link"); 00104 req.allowed_contacts[0].link_names.push_back("r_forearm_link"); 00105 req.allowed_contacts[0].link_names.push_back("r_forearm_roll_link"); 00106 req.allowed_contacts[0].link_names.push_back("r_wrist_flex_link"); 00107 req.allowed_contacts[0].link_names.push_back("r_wrist_roll_link"); 00108 req.allowed_contacts[0].link_names.push_back("r_gripper_l_finger_link"); 00109 req.allowed_contacts[0].link_names.push_back("r_gripper_palm_link"); 00110 req.allowed_contacts[0].penetration_depth = 3.0; 00111 00112 EXPECT_TRUE(check_trajectory_validity_client_.call(req,res)); 00113 if(res.error_code.val == res.error_code.SUCCESS) 00114 { 00115 ROS_INFO("Collision not detected with allowable contact region set"); 00116 } 00117 EXPECT_TRUE(res.error_code.val == res.error_code.SUCCESS); 00118 } 00119 00120 int main(int argc, char **argv){ 00121 testing::InitGoogleTest(&argc, argv); 00122 ros::init (argc, argv, "allowable_contacts_test"); 00123 return RUN_ALL_TESTS(); 00124 }