$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 #include <arm_navigation_msgs/utils.h> 00043 00044 #include <boost/thread.hpp> 00045 #include <gtest/gtest.h> 00046 #include <arm_navigation_tests/arm_navigation_utils.h> 00047 00048 typedef actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> MoveArmClient; 00049 00050 void spinThread() 00051 { 00052 ros::spin(); 00053 } 00054 00055 TEST(MoveArm, goToPoseGoal) 00056 { 00057 ros::NodeHandle nh; 00058 ros::NodeHandle private_handle("~"); 00059 actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> move_arm(nh, "move_right_arm"); 00060 boost::thread spin_thread(&spinThread); 00061 00062 move_arm.waitForServer(); 00063 ROS_INFO("Connected to server"); 00064 00065 arm_navigation_utils::ArmNavigationUtils arm_nav_utils; 00066 EXPECT_TRUE(arm_nav_utils.takeStaticMap()); 00067 00068 arm_navigation_msgs::MoveArmGoal goalA; 00069 00070 goalA.motion_plan_request.group_name = "right_arm"; 00071 goalA.motion_plan_request.num_planning_attempts = 1; 00072 private_handle.param<std::string>("planner_id",goalA.motion_plan_request.planner_id,std::string("")); 00073 private_handle.param<std::string>("planner_service_name",goalA.planner_service_name,std::string("ompl_planning/plan_kinematic_path")); 00074 00075 goalA.motion_plan_request.allowed_planning_time = ros::Duration(5.0); 00076 00077 00078 arm_navigation_msgs::SimplePoseConstraint desired_pose; 00079 desired_pose.header.frame_id = "torso_lift_link"; 00080 desired_pose.link_name = "r_wrist_roll_link"; 00081 desired_pose.pose.position.x = 0.75; 00082 desired_pose.pose.position.y = -0.188; 00083 desired_pose.pose.position.z = 0; 00084 00085 desired_pose.pose.orientation.x = 0.0; 00086 desired_pose.pose.orientation.y = 0.0; 00087 desired_pose.pose.orientation.z = 0.0; 00088 desired_pose.pose.orientation.w = 1.0; 00089 00090 desired_pose.absolute_position_tolerance.x = 0.02; 00091 desired_pose.absolute_position_tolerance.y = 0.02; 00092 desired_pose.absolute_position_tolerance.z = 0.02; 00093 00094 desired_pose.absolute_roll_tolerance = 0.04; 00095 desired_pose.absolute_pitch_tolerance = 0.04; 00096 desired_pose.absolute_yaw_tolerance = 0.04; 00097 00098 arm_navigation_msgs::addGoalConstraintToMoveArmGoal(desired_pose,goalA); 00099 00100 int num_test_attempts = 0; 00101 int max_attempts = 5; 00102 bool success = false; 00103 while (nh.ok()) 00104 { 00105 bool finished_within_time = false; 00106 move_arm.sendGoal(goalA); 00107 finished_within_time = move_arm.waitForResult(ros::Duration(100.0)); 00108 actionlib::SimpleClientGoalState state = move_arm.getState(); 00109 success = (state == actionlib::SimpleClientGoalState::SUCCEEDED); 00110 if ((!finished_within_time || !success) && num_test_attempts < max_attempts) 00111 { 00112 move_arm.cancelGoal(); 00113 ROS_INFO("Timed out achieving goal A, trying again. Trying again, attempt: %d",num_test_attempts); 00114 num_test_attempts++; 00115 } 00116 else 00117 { 00118 if(!success) 00119 { 00120 ROS_INFO("Action finished: %s",state.toString().c_str()); 00121 move_arm.cancelGoal(); 00122 } 00123 ROS_INFO("Action finished: %s",state.toString().c_str()); 00124 break; 00125 } 00126 } 00127 EXPECT_TRUE(success); 00128 ros::shutdown(); 00129 spin_thread.join(); 00130 } 00131 00132 int main(int argc, char **argv){ 00133 testing::InitGoogleTest(&argc, argv); 00134 ros::init (argc, argv, "move_arm_regression_test"); 00135 return RUN_ALL_TESTS(); 00136 }