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