$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * 00035 *********************************************************************/ 00036 00037 /* \author: Ioan Sucan, Sachin Chitta */ 00038 00039 #include <ros/ros.h> 00040 #include <actionlib/client/simple_action_client.h> 00041 #include <arm_navigation_msgs/MoveArmAction.h> 00042 00043 #include <stdio.h> 00044 #include <stdlib.h> 00045 #include <time.h> 00046 #include <boost/thread.hpp> 00047 #include <ros/ros.h> 00048 #include <gtest/gtest.h> 00049 00050 #include <arm_navigation_msgs/Shape.h> 00051 #include <arm_navigation_tests/arm_navigation_utils.h> 00052 00053 00054 typedef actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> MoveArmClient; 00055 00056 void spinThread() 00057 { 00058 ros::spin(); 00059 } 00060 00061 TEST(MoveArm, goToPoseGoal) 00062 { 00063 ros::NodeHandle nh; 00064 ros::NodeHandle private_handle("~"); 00065 actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> move_arm(nh, "move_right_arm"); 00066 boost::thread spin_thread(&spinThread); 00067 00068 move_arm.waitForServer(); 00069 ROS_INFO("Connected to server"); 00070 arm_navigation_msgs::MoveArmGoal goalA; 00071 00072 arm_navigation_msgs::CollisionObject static_object_1_; 00073 static_object_1_.header.stamp = ros::Time::now(); 00074 static_object_1_.header.frame_id = "odom_combined"; 00075 static_object_1_.id = "object_1"; 00076 static_object_1_.operation.operation = arm_navigation_msgs::CollisionObjectOperation::ADD; 00077 static_object_1_.shapes.resize(1); 00078 static_object_1_.shapes[0].type = arm_navigation_msgs::Shape::CYLINDER; 00079 static_object_1_.shapes[0].dimensions.resize(2); 00080 static_object_1_.shapes[0].dimensions[0] = .1; 00081 static_object_1_.shapes[0].dimensions[1] = 1.5; 00082 static_object_1_.poses.resize(1); 00083 static_object_1_.poses[0].position.x = .75; 00084 static_object_1_.poses[0].position.y = -.188; 00085 static_object_1_.poses[0].position.z = .91; 00086 static_object_1_.poses[0].orientation.w = 1.0; 00087 00088 goalA.planning_scene_diff.collision_objects.push_back(static_object_1_); 00089 00090 arm_navigation_utils::ArmNavigationUtils arm_nav_utils; 00091 EXPECT_TRUE(arm_nav_utils.takeStaticMap()); 00092 00093 goalA.motion_plan_request.group_name = "right_arm"; 00094 goalA.motion_plan_request.num_planning_attempts = 1; 00095 private_handle.param<std::string>("planner_id",goalA.motion_plan_request.planner_id,std::string("")); 00096 private_handle.param<std::string>("planner_service_name",goalA.planner_service_name,std::string("/ompl_planning/plan_kinematic_path")); 00097 00098 goalA.motion_plan_request.allowed_planning_time = ros::Duration(5.0); 00099 00100 goalA.motion_plan_request.goal_constraints.position_constraints.resize(1); 00101 goalA.motion_plan_request.goal_constraints.position_constraints[0].header.stamp = ros::Time::now(); 00102 goalA.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id = "torso_lift_link"; 00103 00104 //this is intentionally out of reach 00105 goalA.motion_plan_request.goal_constraints.position_constraints[0].link_name = "r_wrist_roll_link"; 00106 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.x = 0.75; 00107 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.y = -0.188; 00108 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.z = 1.2; 00109 00110 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.type = arm_navigation_msgs::Shape::BOX; 00111 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02); 00112 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02); 00113 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02); 00114 00115 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_orientation.w = 1.0; 00116 goalA.motion_plan_request.goal_constraints.position_constraints[0].weight = 1.0; 00117 00118 goalA.motion_plan_request.goal_constraints.orientation_constraints.resize(1); 00119 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.stamp = ros::Time::now(); 00120 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.frame_id = "torso_lift_link"; 00121 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].link_name = "r_wrist_roll_link"; 00122 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.x = 0.0; 00123 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.y = 0.0; 00124 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.z = 0.0; 00125 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.w = 1.0; 00126 00127 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.04; 00128 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.04; 00129 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_yaw_tolerance = 0.04; 00130 00131 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].weight = 1.0; 00132 00133 /* 00134 // These are in here just for reference 00135 std::vector<std::string> names(7); 00136 names[0] = "r_shoulder_pan_joint"; 00137 names[1] = "r_shoulder_lift_joint"; 00138 names[2] = "r_upper_arm_roll_joint"; 00139 names[3] = "r_elbow_flex_joint"; 00140 names[4] = "r_forearm_roll_joint"; 00141 names[5] = "r_wrist_flex_joint"; 00142 names[6] = "r_wrist_roll_joint"; 00143 */ 00144 00145 int num_test_attempts = 0; 00146 int max_attempts = 5; 00147 bool success = false; 00148 while (nh.ok()) 00149 { 00150 bool finished_within_time = false; 00151 move_arm.sendGoal(goalA); 00152 finished_within_time = move_arm.waitForResult(ros::Duration(100.0)); 00153 actionlib::SimpleClientGoalState state = move_arm.getState(); 00154 success = (state == actionlib::SimpleClientGoalState::SUCCEEDED); 00155 if ((!finished_within_time || !success) && num_test_attempts < max_attempts) 00156 { 00157 move_arm.cancelGoal(); 00158 if(!finished_within_time) { 00159 ROS_INFO("Timed out achieving goal A, trying again. Trying again, attempt: %d",num_test_attempts); 00160 } else { 00161 ROS_INFO("Failed achieving goal A, trying again. Trying again, attempt: %d",num_test_attempts); 00162 } 00163 num_test_attempts++; 00164 } 00165 else 00166 { 00167 if(!success) 00168 { 00169 ROS_INFO("Action finished: %s",state.toString().c_str()); 00170 move_arm.cancelGoal(); 00171 } 00172 ROS_INFO("Action finished: %s",state.toString().c_str()); 00173 break; 00174 } 00175 } 00176 EXPECT_FALSE(success); 00177 00178 goalA.planning_scene_diff.collision_objects.pop_back(); 00179 num_test_attempts = 0; 00180 while (nh.ok()) 00181 { 00182 bool finished_within_time = false; 00183 move_arm.sendGoal(goalA); 00184 finished_within_time = move_arm.waitForResult(ros::Duration(100.0)); 00185 actionlib::SimpleClientGoalState state = move_arm.getState(); 00186 success = (state == actionlib::SimpleClientGoalState::SUCCEEDED); 00187 if ((!finished_within_time || !success) && num_test_attempts < max_attempts) 00188 { 00189 move_arm.cancelGoal(); 00190 if(!finished_within_time) { 00191 ROS_INFO("Timed out achieving goal A, trying again. Trying again, attempt: %d",num_test_attempts); 00192 } else { 00193 ROS_INFO("Failed achieving goal A, trying again. Trying again, attempt: %d",num_test_attempts); 00194 } 00195 num_test_attempts++; 00196 } 00197 else 00198 { 00199 if(!success) 00200 { 00201 ROS_INFO("Action finished: %s",state.toString().c_str()); 00202 move_arm.cancelGoal(); 00203 } 00204 ROS_INFO("Action finished: %s",state.toString().c_str()); 00205 break; 00206 } 00207 } 00208 //should still fail 00209 EXPECT_FALSE(success); 00210 00211 00212 ros::shutdown(); 00213 spin_thread.join(); 00214 } 00215 00216 int main(int argc, char **argv){ 00217 testing::InitGoogleTest(&argc, argv); 00218 ros::init (argc, argv, "move_arm_regression_test"); 00219 return RUN_ALL_TESTS(); 00220 }