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 <stdio.h>
00044 #include <stdlib.h>
00045 #include <time.h>
00046 #include <ros/ros.h>
00047 #include <gtest/gtest.h>
00048
00049 #include <arm_navigation_tests/arm_navigation_utils.h>
00050
00051 void spinThread()
00052 {
00053 ros::spin();
00054 }
00055
00056 TEST(MoveArm, goToJointGoal)
00057 {
00058 ros::NodeHandle nh;
00059 ros::NodeHandle private_handle("~");
00060 actionlib::SimpleActionClient<move_arm_msgs::MoveArmAction> move_arm(nh, "move_right_arm");
00061 boost::thread spin_thread(&spinThread);
00062
00063 move_arm.waitForServer();
00064 ROS_INFO("Connected to server");
00065
00066 arm_navigation_utils::ArmNavigationUtils arm_nav_utils;
00067 EXPECT_TRUE(arm_nav_utils.takeStaticMap());
00068
00069 move_arm_msgs::MoveArmGoal goalB;
00070 std::vector<std::string> names(7);
00071 names[0] = "r_shoulder_pan_joint";
00072 names[1] = "r_shoulder_lift_joint";
00073 names[2] = "r_upper_arm_roll_joint";
00074 names[3] = "r_elbow_flex_joint";
00075 names[4] = "r_forearm_roll_joint";
00076 names[5] = "r_wrist_flex_joint";
00077 names[6] = "r_wrist_roll_joint";
00078
00079 goalB.motion_plan_request.group_name = "right_arm";
00080 private_handle.param<std::string>("planner_id",goalB.motion_plan_request.planner_id,std::string("chomp_planner_longrange"));
00081 private_handle.param<std::string>("planner_service_name",goalB.planner_service_name,std::string("/chomp_planner_longrange/plan_path"));
00082
00083 goalB.motion_plan_request.goal_constraints.joint_constraints.resize(names.size());
00084 for (unsigned int i = 0 ; i < goalB.motion_plan_request.goal_constraints.joint_constraints.size(); ++i)
00085 {
00086
00087
00088 goalB.motion_plan_request.goal_constraints.joint_constraints[i].joint_name = names[i];
00089 goalB.motion_plan_request.goal_constraints.joint_constraints[i].position = 0.0;
00090 goalB.motion_plan_request.goal_constraints.joint_constraints[i].tolerance_below = 0.1;
00091 goalB.motion_plan_request.goal_constraints.joint_constraints[i].tolerance_above = 0.1;
00092 }
00093
00094 goalB.motion_plan_request.goal_constraints.joint_constraints[0].position = -2.0;
00095 goalB.motion_plan_request.goal_constraints.joint_constraints[3].position = -0.2;
00096 goalB.motion_plan_request.goal_constraints.joint_constraints[5].position = 0.15;
00097
00098 if (nh.ok())
00099 {
00100 bool finished_within_time = false;
00101 move_arm.sendGoal(goalB);
00102 finished_within_time = move_arm.waitForResult(ros::Duration(10.0));
00103 actionlib::SimpleClientGoalState state = move_arm.getState();
00104 bool success = (state == actionlib::SimpleClientGoalState::ABORTED);
00105 EXPECT_TRUE(success);
00106 ROS_INFO("Action finished: %s",state.toString().c_str());
00107 }
00108 ros::shutdown();
00109 spin_thread.join();
00110 }
00111
00112 int main(int argc, char **argv){
00113 testing::InitGoogleTest(&argc, argv);
00114 ros::init (argc, argv, "move_arm_regression_test");
00115 return RUN_ALL_TESTS();
00116 }