regression_test_pose_goal_both_arms.cpp
Go to the documentation of this file.
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 
00052 typedef actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> MoveArmClient;
00053 
00054 void spinThread()
00055 {
00056   ros::spin();
00057 }
00058 
00059 TEST(MoveArm, goToPoseGoal)
00060 {
00061   ros::NodeHandle nh;
00062   ros::NodeHandle private_handle("~");
00063   actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> move_right_arm(nh, "move_right_arm");
00064   actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> move_left_arm(nh, "move_left_arm");
00065   boost::thread spin_thread(&spinThread);
00066 
00067   move_right_arm.waitForServer();
00068   move_left_arm.waitForServer();
00069   ROS_INFO("Connected to servers");
00070   arm_navigation_msgs::MoveArmGoal goalLeft, goalRight;
00071 
00072   goalRight.motion_plan_request.group_name = "right_arm";
00073   goalRight.motion_plan_request.num_planning_attempts = 1;
00074   private_handle.param<std::string>("planner_id",goalRight.motion_plan_request.planner_id,std::string("chomp_planner_longrange"));
00075   private_handle.param<std::string>("planner_service_name",goalRight.planner_service_name,std::string("/chomp_planner_longrange/plan_path"));
00076 
00077   goalRight.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00078     
00079   goalRight.motion_plan_request.goal_constraints.set_position_constraints_size(1);
00080   goalRight.motion_plan_request.goal_constraints.position_constraints[0].header.stamp = ros::Time::now();
00081   goalRight.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id = "torso_lift_link";
00082     
00083   goalRight.motion_plan_request.goal_constraints.position_constraints[0].link_name = "r_wrist_roll_link";
00084   goalRight.motion_plan_request.goal_constraints.position_constraints[0].position.x = 0.75;
00085   goalRight.motion_plan_request.goal_constraints.position_constraints[0].position.y = -0.188;
00086   goalRight.motion_plan_request.goal_constraints.position_constraints[0].position.z = 0;
00087     
00088   goalRight.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.type = arm_navigation_msgs::Shape::BOX;
00089   goalRight.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00090   goalRight.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00091   goalRight.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00092 
00093   goalRight.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_orientation.w = 1.0;
00094   goalRight.motion_plan_request.goal_constraints.position_constraints[0].weight = 1.0;
00095 
00096   goalRight.motion_plan_request.goal_constraints.set_orientation_constraints_size(1);
00097   goalRight.motion_plan_request.goal_constraints.orientation_constraints[0].header.stamp = ros::Time::now();
00098   goalRight.motion_plan_request.goal_constraints.orientation_constraints[0].header.frame_id = "torso_lift_link";    
00099   goalRight.motion_plan_request.goal_constraints.orientation_constraints[0].link_name = "r_wrist_roll_link";
00100   goalRight.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.x = 0.0;
00101   goalRight.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.y = 0.0;
00102   goalRight.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.z = 0.0;
00103   goalRight.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.w = 1.0;
00104     
00105   goalRight.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.04;
00106   goalRight.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.04;
00107   goalRight.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_yaw_tolerance = 0.04;
00108 
00109   goalRight.motion_plan_request.goal_constraints.orientation_constraints[0].weight = 1.0;
00110 
00111 
00112 
00113 
00114   goalLeft.motion_plan_request.group_name = "left_arm";
00115   goalLeft.motion_plan_request.num_planning_attempts = 1;
00116   private_handle.param<std::string>("planner_id",goalLeft.motion_plan_request.planner_id,std::string("chomp_planner_longrange"));
00117   private_handle.param<std::string>("planner_service_name",goalLeft.planner_service_name,std::string("/chomp_planner_longrange/plan_path"));
00118 
00119   goalLeft.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00120     
00121   goalLeft.motion_plan_request.goal_constraints.set_position_constraints_size(1);
00122   goalLeft.motion_plan_request.goal_constraints.position_constraints[0].header.stamp = ros::Time::now();
00123   goalLeft.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id = "torso_lift_link";
00124     
00125   goalLeft.motion_plan_request.goal_constraints.position_constraints[0].link_name = "l_wrist_roll_link";
00126   goalLeft.motion_plan_request.goal_constraints.position_constraints[0].position.x = 0.75;
00127   goalLeft.motion_plan_request.goal_constraints.position_constraints[0].position.y = 0.188;
00128   goalLeft.motion_plan_request.goal_constraints.position_constraints[0].position.z = 0;
00129     
00130   goalLeft.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.type = arm_navigation_msgs::Shape::BOX;
00131   goalLeft.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00132   goalLeft.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00133   goalLeft.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00134 
00135   goalLeft.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_orientation.w = 1.0;
00136   goalLeft.motion_plan_request.goal_constraints.position_constraints[0].weight = 1.0;
00137 
00138   goalLeft.motion_plan_request.goal_constraints.set_orientation_constraints_size(1);
00139   goalLeft.motion_plan_request.goal_constraints.orientation_constraints[0].header.stamp = ros::Time::now();
00140   goalLeft.motion_plan_request.goal_constraints.orientation_constraints[0].header.frame_id = "torso_lift_link";    
00141   goalLeft.motion_plan_request.goal_constraints.orientation_constraints[0].link_name = "l_wrist_roll_link";
00142   goalLeft.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.x = 0.0;
00143   goalLeft.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.y = 0.0;
00144   goalLeft.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.z = 0.0;
00145   goalLeft.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.w = 1.0;
00146     
00147   goalLeft.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.04;
00148   goalLeft.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.04;
00149   goalLeft.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_yaw_tolerance = 0.04;
00150 
00151   goalLeft.motion_plan_request.goal_constraints.orientation_constraints[0].weight = 1.0;
00152 
00153   /*   
00154   // These are in here just for reference
00155   std::vector<std::string> names(7);
00156   names[0] = "r_shoulder_pan_joint";
00157   names[1] = "r_shoulder_lift_joint";
00158   names[2] = "r_upper_arm_roll_joint";
00159   names[3] = "r_elbow_flex_joint";
00160   names[4] = "r_forearm_roll_joint";
00161   names[5] = "r_wrist_flex_joint";
00162   names[6] = "r_wrist_roll_joint";
00163   */
00164 
00165   int num_test_attempts = 0;
00166   int max_attempts = 5;
00167   bool success = false;
00168   while (nh.ok())
00169   {
00170     bool right_finished_within_time = false;
00171     bool left_finished_within_time = false;
00172     move_right_arm.sendGoal(goalRight);
00173     move_left_arm.sendGoal(goalLeft);
00174     
00175     right_finished_within_time = move_right_arm.waitForResult(ros::Duration(200.0));
00176     left_finished_within_time = move_left_arm.waitForResult(ros::Duration(10.0));
00177     
00178     actionlib::SimpleClientGoalState right_state = move_right_arm.getState();
00179     actionlib::SimpleClientGoalState left_state = move_left_arm.getState();
00180     success = (right_state == actionlib::SimpleClientGoalState::SUCCEEDED && left_state == actionlib::SimpleClientGoalState::SUCCEEDED);
00181     if(!right_finished_within_time || right_state != actionlib::SimpleClientGoalState::SUCCEEDED) {
00182       move_right_arm.cancelGoal();
00183       ROS_INFO("Right arm timed out achieving goal");
00184     }
00185     if(!left_finished_within_time || left_state != actionlib::SimpleClientGoalState::SUCCEEDED) {
00186       move_left_arm.cancelGoal();
00187       ROS_INFO("Left arm timed out achieving goal");
00188     }
00189     if(!success) {
00190       num_test_attempts++;
00191       if(num_test_attempts > max_attempts) {
00192         break;
00193       }
00194     } else {
00195       break;
00196     }
00197   }
00198   EXPECT_TRUE(success);
00199   ros::shutdown();
00200   spin_thread.join();
00201 }
00202 
00203 int main(int argc, char **argv){
00204   testing::InitGoogleTest(&argc, argv);
00205   ros::init (argc, argv, "move_arm_regression_test");
00206   return RUN_ALL_TESTS();
00207 }


move_arm
Author(s): Ioan Sucan, Sachin Chitta(sachinc@willowgarage.com)
autogenerated on Mon Dec 2 2013 12:35:17