$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 <ros/ros.h> 00047 #include <gtest/gtest.h> 00048 00049 #include <arm_navigation_tests/arm_navigation_utils.h> 00050 00051 void spinThread() 00052 { 00053 ros::spin(); 00054 } 00055 00056 TEST(MoveArm, goToJointGoal) 00057 { 00058 ros::NodeHandle nh; 00059 ros::NodeHandle private_handle("~"); 00060 actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> move_arm(nh, "move_right_arm"); 00061 boost::thread spin_thread(&spinThread); 00062 00063 move_arm.waitForServer(); 00064 ROS_INFO("Connected to server"); 00065 00066 arm_navigation_utils::ArmNavigationUtils arm_nav_utils; 00067 EXPECT_TRUE(arm_nav_utils.takeStaticMap()); 00068 00069 arm_navigation_msgs::MoveArmGoal goalB; 00070 std::vector<std::string> names(7); 00071 names[0] = "r_shoulder_pan_joint"; 00072 names[1] = "r_shoulder_lift_joint"; 00073 names[2] = "r_upper_arm_roll_joint"; 00074 names[3] = "r_elbow_flex_joint"; 00075 names[4] = "r_forearm_roll_joint"; 00076 names[5] = "r_wrist_flex_joint"; 00077 names[6] = "r_wrist_roll_joint"; 00078 00079 goalB.motion_plan_request.group_name = "right_arm"; 00080 goalB.motion_plan_request.num_planning_attempts = 1; 00081 goalB.motion_plan_request.allowed_planning_time = ros::Duration(5.0); 00082 00083 private_handle.param<std::string>("planner_id",goalB.motion_plan_request.planner_id,std::string("chomp_planner_longrange")); 00084 private_handle.param<std::string>("planner_service_name",goalB.planner_service_name,std::string("/chomp_planner_longrange/plan_path")); 00085 00086 goalB.motion_plan_request.goal_constraints.joint_constraints.resize(names.size()); 00087 for (unsigned int i = 0 ; i < goalB.motion_plan_request.goal_constraints.joint_constraints.size(); ++i) 00088 { 00089 // goalB.motion_plan_request.goal_constraints.joint_constraints[i].header.stamp = ros::Time::now(); 00090 // goalB.motion_plan_request.goal_constraints.joint_constraints[i].header.frame_id = "base_link"; 00091 goalB.motion_plan_request.goal_constraints.joint_constraints[i].joint_name = names[i]; 00092 goalB.motion_plan_request.goal_constraints.joint_constraints[i].position = 0.0; 00093 goalB.motion_plan_request.goal_constraints.joint_constraints[i].tolerance_below = 0.1; 00094 goalB.motion_plan_request.goal_constraints.joint_constraints[i].tolerance_above = 0.1; 00095 } 00096 00097 goalB.motion_plan_request.goal_constraints.joint_constraints[0].position = -2.0; 00098 goalB.motion_plan_request.goal_constraints.joint_constraints[3].position = -0.2; 00099 goalB.motion_plan_request.goal_constraints.joint_constraints[5].position = -0.20; 00100 00101 int num_test_attempts = 0; 00102 int max_attempts = 5; 00103 bool success = false; 00104 while (nh.ok()) 00105 { 00106 bool finished_within_time = false; 00107 move_arm.sendGoal(goalB); 00108 finished_within_time = move_arm.waitForResult(ros::Duration(200.0)); 00109 actionlib::SimpleClientGoalState state = move_arm.getState(); 00110 success = (state == actionlib::SimpleClientGoalState::SUCCEEDED); 00111 if ((!finished_within_time || !success) && num_test_attempts < max_attempts) 00112 { 00113 move_arm.cancelGoal(); 00114 ROS_INFO("Timed out achieving goal A"); 00115 num_test_attempts++; 00116 } 00117 else 00118 { 00119 if(!success) 00120 { 00121 ROS_INFO("Action finished: %s",state.toString().c_str()); 00122 move_arm.cancelGoal(); 00123 } 00124 ROS_INFO("Action finished: %s",state.toString().c_str()); 00125 break; 00126 } 00127 } 00128 EXPECT_TRUE(success); 00129 ros::shutdown(); 00130 spin_thread.join(); 00131 } 00132 00133 int main(int argc, char **argv){ 00134 testing::InitGoogleTest(&argc, argv); 00135 ros::init (argc, argv, "move_arm_regression_test"); 00136 return RUN_ALL_TESTS(); 00137 }