Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
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
00155
00156
00157
00158
00159
00160
00161
00162
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 }