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/MoveArmAction.h>
00042
00043 #include <vector>
00044 #include <string>
00045
00046 int main(int argc, char **argv)
00047 {
00048 ros::init(argc, argv, "test_move_right_arm");
00049 ros::NodeHandle nh;
00050
00051 actionlib::SimpleActionClient<move_arm::MoveArmAction> move_arm(nh, "move_right_arm");
00052
00053 move_arm::MoveArmGoal goalA;
00054 move_arm::MoveArmGoal goalB;
00055
00056 goalA.goal_constraints.set_pose_constraint_size(1);
00057 goalA.goal_constraints.pose_constraint[0].pose.header.stamp = ros::Time::now();
00058 goalA.goal_constraints.pose_constraint[0].pose.header.frame_id = "torso_lift_link";
00059
00060 goalA.goal_constraints.pose_constraint[0].link_name = "r_wrist_roll_link";
00061 goalA.goal_constraints.pose_constraint[0].pose.pose.position.x = 0.75;
00062 goalA.goal_constraints.pose_constraint[0].pose.pose.position.y = -0.188;
00063 goalA.goal_constraints.pose_constraint[0].pose.pose.position.z = 0;
00064
00065 goalA.goal_constraints.pose_constraint[0].pose.pose.orientation.x = 0;
00066 goalA.goal_constraints.pose_constraint[0].pose.pose.orientation.y = 0;
00067 goalA.goal_constraints.pose_constraint[0].pose.pose.orientation.z = 0;
00068 goalA.goal_constraints.pose_constraint[0].pose.pose.orientation.w = 1;
00069
00070 goalA.goal_constraints.pose_constraint[0].position_tolerance_above.x = 0.003;
00071 goalA.goal_constraints.pose_constraint[0].position_tolerance_above.y = 0.003;
00072 goalA.goal_constraints.pose_constraint[0].position_tolerance_above.z = 0.003;
00073 goalA.goal_constraints.pose_constraint[0].position_tolerance_below.x = 0.003;
00074 goalA.goal_constraints.pose_constraint[0].position_tolerance_below.y = 0.003;
00075 goalA.goal_constraints.pose_constraint[0].position_tolerance_below.z = 0.003;
00076
00077 goalA.goal_constraints.pose_constraint[0].orientation_tolerance_above.x = 0.005;
00078 goalA.goal_constraints.pose_constraint[0].orientation_tolerance_above.y = 0.005;
00079 goalA.goal_constraints.pose_constraint[0].orientation_tolerance_above.z = 0.005;
00080 goalA.goal_constraints.pose_constraint[0].orientation_tolerance_below.x = 0.005;
00081 goalA.goal_constraints.pose_constraint[0].orientation_tolerance_below.y = 0.005;
00082 goalA.goal_constraints.pose_constraint[0].orientation_tolerance_below.z = 0.005;
00083
00084 goalA.goal_constraints.pose_constraint[0].orientation_importance = 0.1;
00085 goalA.goal_constraints.pose_constraint[0].type =
00086 motion_planning_msgs::PoseConstraint::POSITION_X + motion_planning_msgs::PoseConstraint::POSITION_Y + motion_planning_msgs::PoseConstraint::POSITION_Z +
00087 motion_planning_msgs::PoseConstraint::ORIENTATION_R + motion_planning_msgs::PoseConstraint::ORIENTATION_P + motion_planning_msgs::PoseConstraint::ORIENTATION_Y;
00088
00089
00090 std::vector<std::string> names(7);
00091 names[0] = "r_shoulder_pan_joint";
00092 names[1] = "r_shoulder_lift_joint";
00093 names[2] = "r_upper_arm_roll_joint";
00094 names[3] = "r_elbow_flex_joint";
00095 names[4] = "r_forearm_roll_joint";
00096 names[5] = "r_wrist_flex_joint";
00097 names[6] = "r_wrist_roll_joint";
00098
00099 goalB.goal_constraints.joint_constraint.resize(names.size());
00100 for (unsigned int i = 0 ; i < goalB.goal_constraints.joint_constraint.size(); ++i)
00101 {
00102 goalB.goal_constraints.joint_constraint[i].header.stamp = ros::Time::now();
00103 goalB.goal_constraints.joint_constraint[i].header.frame_id = "base_link";
00104 goalB.goal_constraints.joint_constraint[i].joint_name = names[i];
00105 goalB.goal_constraints.joint_constraint[i].value.resize(1);
00106 goalB.goal_constraints.joint_constraint[i].tolerance_above.resize(1);
00107 goalB.goal_constraints.joint_constraint[i].tolerance_below.resize(1);
00108 goalB.goal_constraints.joint_constraint[i].value[0] = 0.0;
00109 goalB.goal_constraints.joint_constraint[i].tolerance_below[0] = 0.0;
00110 goalB.goal_constraints.joint_constraint[i].tolerance_above[0] = 0.0;
00111 }
00112
00113 goalB.goal_constraints.joint_constraint[0].value[0] = -2.0;
00114 goalB.goal_constraints.joint_constraint[3].value[0] = -0.1;
00115 goalB.goal_constraints.joint_constraint[5].value[0] = 0.15;
00116
00117 while (nh.ok())
00118 {
00119 ros::spinOnce();
00120
00121 bool finished_within_time;
00122 move_arm.sendGoal(goalA);
00123 finished_within_time = move_arm.waitForGoalToFinish(ros::Duration(10.0));
00124
00125 if (!finished_within_time)
00126 {
00127 move_arm.cancelGoal();
00128 std::cerr << "Timed out achieving goal A" << std::endl;
00129 }
00130 else
00131 std::cout << "Final state is " << move_arm.getTerminalState().toString() << std::endl;
00132
00133 move_arm.sendGoal(goalB);
00134 finished_within_time = move_arm.waitForGoalToFinish(ros::Duration(10.0));
00135
00136 if (!finished_within_time)
00137 {
00138 move_arm.cancelGoal();
00139 std::cerr << "Timed out achieving goal B" << std::endl;
00140 }
00141 else
00142 std::cout << "Final state is " << move_arm.getTerminalState().toString() << std::endl;
00143 }
00144
00145 return 0;
00146 }