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_arm(nh, "move_right_arm");
00064 boost::thread spin_thread(&spinThread);
00065
00066 move_arm.waitForServer();
00067 ROS_INFO("Connected to server");
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("chomp_planner_longrange"));
00073 private_handle.param<std::string>("planner_service_name",goalA.planner_service_name,std::string("/chomp_planner_longrange/plan_path"));
00074
00075 goalA.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00076
00077 goalA.motion_plan_request.goal_constraints.set_position_constraints_size(1);
00078 goalA.motion_plan_request.goal_constraints.position_constraints[0].header.stamp = ros::Time::now();
00079 goalA.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id = "torso_lift_link";
00080
00081 goalA.motion_plan_request.goal_constraints.position_constraints[0].link_name = "r_wrist_roll_link";
00082 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.x = 0.75;
00083 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.y = -0.188;
00084 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.z = 0;
00085
00086 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.type = arm_navigation_msgs::Shape::BOX;
00087 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00088 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00089 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00090
00091 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_orientation.w = 1.0;
00092 goalA.motion_plan_request.goal_constraints.position_constraints[0].weight = 1.0;
00093
00094 goalA.motion_plan_request.goal_constraints.set_orientation_constraints_size(1);
00095 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.stamp = ros::Time::now();
00096 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.frame_id = "torso_lift_link";
00097 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].link_name = "r_wrist_roll_link";
00098 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.x = 0.0;
00099 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.y = 0.0;
00100 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.z = 0.0;
00101 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.w = 1.0;
00102
00103 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.04;
00104 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.04;
00105 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_yaw_tolerance = 0.04;
00106
00107 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].weight = 1.0;
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121 int num_test_attempts = 0;
00122 int max_attempts = 5;
00123 bool success = false;
00124 while (nh.ok())
00125 {
00126 bool finished_within_time = false;
00127 move_arm.sendGoal(goalA);
00128 finished_within_time = move_arm.waitForResult(ros::Duration(100.0));
00129 actionlib::SimpleClientGoalState state = move_arm.getState();
00130 success = (state == actionlib::SimpleClientGoalState::SUCCEEDED);
00131 if ((!finished_within_time || !success) && num_test_attempts < max_attempts)
00132 {
00133 move_arm.cancelGoal();
00134 ROS_INFO("Timed out achieving goal A, trying again. Trying again, attempt: %d",num_test_attempts);
00135 num_test_attempts++;
00136 }
00137 else
00138 {
00139 if(!success)
00140 {
00141 ROS_INFO("Action finished: %s",state.toString().c_str());
00142 move_arm.cancelGoal();
00143 }
00144 ROS_INFO("Action finished: %s",state.toString().c_str());
00145 break;
00146 }
00147 }
00148 EXPECT_TRUE(success);
00149 ros::shutdown();
00150 spin_thread.join();
00151 }
00152
00153 int main(int argc, char **argv){
00154 testing::InitGoogleTest(&argc, argv);
00155 ros::init (argc, argv, "move_arm_regression_test");
00156 return RUN_ALL_TESTS();
00157 }