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 <move_arm_msgs/MoveArmAction.h>
00042
00043 #include <geometry_msgs/Quaternion.h>
00044 #include <tf/tf.h>
00045
00046 #include <stdio.h>
00047 #include <stdlib.h>
00048 #include <time.h>
00049 #include <boost/thread.hpp>
00050 #include <ros/ros.h>
00051 #include <gtest/gtest.h>
00052
00053 #include <arm_navigation_tests/arm_navigation_utils.h>
00054
00055 typedef actionlib::SimpleActionClient<move_arm_msgs::MoveArmAction> MoveArmClient;
00056
00057 void spinThread()
00058 {
00059 ros::spin();
00060 }
00061
00062 TEST(MoveArm, goToPoseGoal)
00063 {
00064 ros::NodeHandle nh;
00065 ros::NodeHandle private_handle("~");
00066 actionlib::SimpleActionClient<move_arm_msgs::MoveArmAction> move_arm(nh, "move_right_arm");
00067 boost::thread spin_thread(&spinThread);
00068
00069 move_arm.waitForServer();
00070
00071 arm_navigation_utils::ArmNavigationUtils arm_nav_utils;
00072 EXPECT_TRUE(arm_nav_utils.takeStaticMap());
00073
00074 ROS_INFO("Connected to server");
00075 move_arm_msgs::MoveArmGoal goalA;
00076
00077 goalA.motion_plan_request.group_name = "right_arm";
00078 goalA.motion_plan_request.num_planning_attempts = 1;
00079 private_handle.param<std::string>("planner_id",goalA.motion_plan_request.planner_id,std::string("chomp_planner_longrange"));
00080 private_handle.param<std::string>("planner_service_name",goalA.planner_service_name,std::string("/chomp_planner_longrange/plan_path"));
00081
00082 double goal_x, goal_y, goal_z, goal_roll, goal_pitch, goal_yaw;
00083 private_handle.param<double>("goal_x",goal_x,0.75);
00084 private_handle.param<double>("goal_y",goal_y,-0.188);
00085 private_handle.param<double>("goal_z",goal_z,0.0);
00086
00087 private_handle.param<double>("goal_roll",goal_roll,0.0);
00088 private_handle.param<double>("goal_pitch",goal_pitch,0.0);
00089 private_handle.param<double>("goal_yaw",goal_yaw,0.0);
00090
00091 btQuaternion gripper_goal;
00092 geometry_msgs::Quaternion gripper_goal_msg;
00093 gripper_goal.setRPY(goal_roll,goal_pitch,goal_yaw);
00094 tf::quaternionTFToMsg(gripper_goal,gripper_goal_msg);
00095
00096 goalA.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00097
00098 goalA.motion_plan_request.goal_constraints.position_constraints.resize(1);
00099 goalA.motion_plan_request.goal_constraints.position_constraints[0].header.stamp = ros::Time::now();
00100 goalA.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id = "torso_lift_link";
00101
00102 goalA.motion_plan_request.goal_constraints.position_constraints[0].link_name = "r_wrist_roll_link";
00103 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.x = goal_x;
00104 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.y = goal_y;
00105 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.z = goal_z;
00106
00107 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.type = geometric_shapes_msgs::Shape::BOX;
00108 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00109 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00110 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00111
00112 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_orientation.w = 1.0;
00113
00114 goalA.motion_plan_request.goal_constraints.position_constraints[0].weight = 1.0;
00115
00116 goalA.motion_plan_request.goal_constraints.orientation_constraints.resize(1);
00117 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.stamp = ros::Time::now();
00118 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.frame_id = "torso_lift_link";
00119 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].link_name = "r_wrist_roll_link";
00120 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.x = gripper_goal_msg.x;
00121 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.y = gripper_goal_msg.y;
00122 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.z = gripper_goal_msg.z;
00123 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.w = gripper_goal_msg.w;
00124
00125 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.04;
00126 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.04;
00127 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_yaw_tolerance = 0.04;
00128
00129 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].weight = 1.0;
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143 int num_test_attempts = 0;
00144 int max_attempts = 5;
00145 bool success = false;
00146 while (nh.ok())
00147 {
00148 bool finished_within_time = false;
00149 move_arm.sendGoal(goalA);
00150 finished_within_time = move_arm.waitForResult(ros::Duration(100.0));
00151 actionlib::SimpleClientGoalState state = move_arm.getState();
00152 success = (state == actionlib::SimpleClientGoalState::SUCCEEDED);
00153 if ((!finished_within_time || !success) && num_test_attempts < max_attempts)
00154 {
00155 move_arm.cancelGoal();
00156 ROS_INFO("Timed out achieving goal A, trying again. Trying again, attempt: %d",num_test_attempts);
00157 num_test_attempts++;
00158 }
00159 else
00160 {
00161 if(!success)
00162 {
00163 ROS_INFO("Action finished %s",state.toString().c_str());
00164 move_arm.cancelGoal();
00165 }
00166 ROS_INFO("Action finished: %s",state.toString().c_str());
00167 break;
00168 }
00169 }
00170 EXPECT_TRUE(success);
00171 ros::shutdown();
00172 spin_thread.join();
00173 }
00174
00175 int main(int argc, char **argv){
00176 testing::InitGoogleTest(&argc, argv);
00177 ros::init (argc, argv, "move_arm_regression_test");
00178 return RUN_ALL_TESTS();
00179 }