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 #include <arm_navigation_msgs/utils.h>
00043
00044 #include <boost/thread.hpp>
00045 #include <gtest/gtest.h>
00046
00047 typedef actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> MoveArmClient;
00048
00049 void spinThread()
00050 {
00051 ros::spin();
00052 }
00053
00054 TEST(MoveArm, goToPoseGoal)
00055 {
00056 ros::NodeHandle nh;
00057 ros::NodeHandle private_handle("~");
00058 actionlib::SimpleActionClient<arm_navigation_msgs::MoveArmAction> move_arm(nh, "move_right_arm");
00059 boost::thread spin_thread(&spinThread);
00060
00061 move_arm.waitForServer();
00062 ROS_INFO("Connected to server");
00063 arm_navigation_msgs::MoveArmGoal goalA;
00064
00065 goalA.motion_plan_request.group_name = "right_arm";
00066 goalA.motion_plan_request.num_planning_attempts = 1;
00067 private_handle.param<std::string>("planner_id",goalA.motion_plan_request.planner_id,std::string(""));
00068 private_handle.param<std::string>("planner_service_name",goalA.planner_service_name,std::string("ompl_planning/plan_kinematic_path"));
00069
00070 goalA.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00071
00072
00073 arm_navigation_msgs::SimplePoseConstraint desired_pose;
00074 desired_pose.header.frame_id = "torso_lift_link";
00075 desired_pose.link_name = "r_wrist_roll_link";
00076 desired_pose.pose.position.x = 0.75;
00077 desired_pose.pose.position.y = -0.188;
00078 desired_pose.pose.position.z = 0;
00079
00080 desired_pose.pose.orientation.x = 0.0;
00081 desired_pose.pose.orientation.y = 0.0;
00082 desired_pose.pose.orientation.z = 0.0;
00083 desired_pose.pose.orientation.w = 1.0;
00084
00085 desired_pose.absolute_position_tolerance.x = 0.02;
00086 desired_pose.absolute_position_tolerance.y = 0.02;
00087 desired_pose.absolute_position_tolerance.z = 0.02;
00088
00089 desired_pose.absolute_roll_tolerance = 0.04;
00090 desired_pose.absolute_pitch_tolerance = 0.04;
00091 desired_pose.absolute_yaw_tolerance = 0.04;
00092
00093 arm_navigation_msgs::addGoalConstraintToMoveArmGoal(desired_pose,goalA);
00094
00095 int num_test_attempts = 0;
00096 int max_attempts = 5;
00097 bool success = false;
00098 while (nh.ok())
00099 {
00100 bool finished_within_time = false;
00101 move_arm.sendGoal(goalA);
00102 finished_within_time = move_arm.waitForResult(ros::Duration(100.0));
00103 actionlib::SimpleClientGoalState state = move_arm.getState();
00104 success = (state == actionlib::SimpleClientGoalState::SUCCEEDED);
00105 if ((!finished_within_time || !success) && num_test_attempts < max_attempts)
00106 {
00107 move_arm.cancelGoal();
00108 ROS_INFO("Timed out achieving goal A, trying again. Trying again, attempt: %d",num_test_attempts);
00109 num_test_attempts++;
00110 }
00111 else
00112 {
00113 if(!success)
00114 {
00115 ROS_INFO("Action finished: %s",state.toString().c_str());
00116 move_arm.cancelGoal();
00117 }
00118 ROS_INFO("Action finished: %s",state.toString().c_str());
00119 break;
00120 }
00121 }
00122 EXPECT_TRUE(success);
00123 ros::shutdown();
00124 spin_thread.join();
00125 }
00126
00127 int main(int argc, char **argv){
00128 testing::InitGoogleTest(&argc, argv);
00129 ros::init (argc, argv, "move_arm_regression_test");
00130 return RUN_ALL_TESTS();
00131 }