00001
00002
00003
00004
00005
00006
00007
00008 #define HALF_SQRT_TWO 0.707106781
00009
00010
00011 #include <simple_robot_control/arm_control.h>
00012 #include <tf/transform_listener.h>
00013 #include <move_arm_msgs/utils.h>
00014 #include <simple_robot_control/ReturnJointStates.h>
00015
00016 namespace simple_robot_control{
00017
00018 Arm::Arm(char arm_side, bool collision_checking): armside_str (&arm_side, 1), move_arm_client_(NULL),
00019 traj_client_(string(armside_str) + "_arm_controller/joint_trajectory_action", true)
00020 {
00021 if (arm_side !='l' && arm_side != 'r' ) ROS_ERROR("Arm:specify l or r for arm side");
00022
00023
00024 joint_names.reserve(7);
00025 joint_names.push_back(armside_str+"_shoulder_pan_joint");
00026 joint_names.push_back(armside_str +"_shoulder_lift_joint");
00027 joint_names.push_back(armside_str +"_upper_arm_roll_joint");
00028 joint_names.push_back(armside_str +"_elbow_flex_joint");
00029 joint_names.push_back(armside_str +"_forearm_roll_joint");
00030 joint_names.push_back(armside_str +"_wrist_flex_joint");
00031 joint_names.push_back(armside_str +"_wrist_roll_joint");
00032
00033 std::string ik_service_name;
00034 if(arm_side == 'r'){
00035 ik_service_name = "pr2_right_arm_kinematics/get_ik";
00036 }else{
00037 ik_service_name = "pr2_left_arm_kinematics/get_ik";
00038 }
00039
00040 if (!ros::service::waitForService(ik_service_name, ros::Duration(5.0))){
00041 ROS_ERROR("Could not find ik server %s", ik_service_name.c_str());
00042 }
00043 ik_service_client_ = nh_.serviceClient<kinematics_msgs::GetPositionIK>(ik_service_name);
00044
00045
00046
00047 if(!traj_client_.waitForServer(ros::Duration(15.0))){
00048 ROS_ERROR("Could not find joint_trajectory_action server %s", (armside_str + "_arm_controller/joint_trajectory_action").c_str());
00049 }
00050
00051 if (collision_checking){
00052 if(arm_side == 'r'){
00053 group_name = "right_arm";
00054 move_arm_client_ = new actionlib::SimpleActionClient<move_arm_msgs::MoveArmAction>("move_right_arm",true);
00055 }
00056 else if (arm_side == 'l'){
00057 group_name = "left_arm";
00058 move_arm_client_ = new actionlib::SimpleActionClient<move_arm_msgs::MoveArmAction>("move_left_arm",true);
00059 }
00060
00061 else{
00062 ROS_ERROR("WRONG ARM NAME");
00063
00064 }
00065
00066 if(!move_arm_client_->waitForServer(ros::Duration(5.0))){
00067 ROS_INFO("could not find collision move arm client");
00068 move_arm_client_ = NULL;
00069 }
00070 }
00071 updateJointStatePos();
00072
00073
00074 }
00075
00077 Arm::~Arm()
00078 {
00079 delete move_arm_client_;
00080
00081 }
00082
00083
00084
00085 bool Arm::moveWristRollLinktoPose(const tf::StampedTransform& tf, double max_time, bool wait, vector<double>* ik_seed_pos ){
00086 geometry_msgs::PoseStamped pose;
00087 tf::Stamped<tf::Pose> tf_pose(tf,tf.stamp_, tf.frame_id_);
00088
00089 tf::poseStampedTFToMsg(tf_pose,pose);
00090 return moveWristRollLinktoPose(pose, max_time, wait, ik_seed_pos);
00091
00092 }
00093
00094 bool Arm::moveWristRollLinktoPoseWithCollisionChecking(const tf::StampedTransform& tf, double max_time, bool wait, std::string planner){
00095 geometry_msgs::PoseStamped pose;
00096 tf::Stamped<tf::Pose> tf_pose(tf,tf.stamp_, tf.frame_id_);
00097
00098 tf::poseStampedTFToMsg(tf_pose,pose);
00099 return moveWristRollLinktoPoseWithCollisionChecking(pose, max_time, wait, planner);
00100 }
00101
00102
00103 bool Arm::goToJointPosWithCollisionChecking(const vector<double>& positions, double max_time, bool wait){
00104
00105 if (!move_arm_client_){
00106 ROS_ERROR("collosion checking arm server has not been started");
00107 return false;
00108 }
00109 move_arm_msgs::MoveArmGoal goalB;
00110
00111 goalB.motion_plan_request.group_name = group_name;
00112 goalB.motion_plan_request.num_planning_attempts = 1;
00113 goalB.motion_plan_request.allowed_planning_time = ros::Duration(max_time);
00114
00115 goalB.motion_plan_request.planner_id= std::string("");
00116 goalB.planner_service_name = std::string("ompl_planning/plan_kinematic_path");
00117 goalB.motion_plan_request.goal_constraints.joint_constraints.resize(7);
00118
00119 for (unsigned int i = 0 ; i < goalB.motion_plan_request.goal_constraints.joint_constraints.size(); ++i)
00120 {
00121 goalB.motion_plan_request.goal_constraints.joint_constraints[i].joint_name = joint_names[i];
00122 goalB.motion_plan_request.goal_constraints.joint_constraints[i].position = positions[i];
00123 goalB.motion_plan_request.goal_constraints.joint_constraints[i].tolerance_below = 0.1;
00124 goalB.motion_plan_request.goal_constraints.joint_constraints[i].tolerance_above = 0.1;
00125 }
00126
00127
00128 bool finished_within_time = false;
00129 bool success = false;
00130 move_arm_client_->sendGoal(goalB);
00131 finished_within_time = move_arm_client_->waitForResult(ros::Duration(5*max_time));
00132 if (!finished_within_time)
00133 {
00134 move_arm_client_->cancelGoal();
00135 ROS_INFO("Timed out achieving JointPos goal");
00136 }
00137 else
00138 {
00139 actionlib::SimpleClientGoalState state = move_arm_client_->getState();
00140 success = (state == actionlib::SimpleClientGoalState::SUCCEEDED);
00141 if(success)
00142 ROS_INFO("Action finished: %s",state.toString().c_str());
00143 else
00144 ROS_INFO("Action failed: %s",state.toString().c_str());
00145 }
00146
00147 return finished_within_time && success;
00148
00149
00150
00151 }
00152
00153 bool Arm::moveWristRollLinktoPoseWithCollisionChecking(const geometry_msgs::PoseStamped& pose, double max_time , bool wait, std::string planner ){
00154
00155
00156 if (!move_arm_client_){
00157 ROS_ERROR("collision checking arm server has not been started");
00158 return false;
00159 }
00160 move_arm_msgs::MoveArmGoal goalA;
00161
00162 goalA.motion_plan_request.group_name = group_name;
00163 goalA.motion_plan_request.num_planning_attempts = 1;
00164 goalA.motion_plan_request.planner_id = std::string("");
00165 if (planner == "chomp"){
00166 ROS_INFO("using chomp planner");
00167 goalA.planner_service_name = std::string("/chomp_planner_longrange/plan_path");
00168 }else{
00169 ROS_INFO("using ompl planner");
00170 goalA.planner_service_name = std::string("ompl_planning/plan_kinematic_path");
00171 }
00172
00173
00174
00175 goalA.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00176
00177 motion_planning_msgs::SimplePoseConstraint desired_pose;
00178
00179 desired_pose.header.frame_id = pose.header.frame_id;
00180 desired_pose.link_name = armside_str + "_wrist_roll_link";
00181 desired_pose.pose = pose.pose;
00182
00183 desired_pose.absolute_position_tolerance.x = 0.02;
00184 desired_pose.absolute_position_tolerance.y = 0.02;
00185 desired_pose.absolute_position_tolerance.z = 0.02;
00186
00187 desired_pose.absolute_roll_tolerance = 0.04;
00188 desired_pose.absolute_pitch_tolerance = 0.04;
00189 desired_pose.absolute_yaw_tolerance = 0.04;
00190
00191 move_arm_msgs::addGoalConstraintToMoveArmGoal(desired_pose,goalA);
00192
00193 move_arm_client_->sendGoal(goalA);
00194 bool finished_before_timeout = false;
00195 bool success = false;
00196
00197 if (wait){
00198 finished_before_timeout = move_arm_client_->waitForResult(ros::Duration(40.0));
00199 if (finished_before_timeout)
00200 {
00201 actionlib::SimpleClientGoalState state = move_arm_client_->getState();
00202 success = (state == actionlib::SimpleClientGoalState::SUCCEEDED);
00203 ROS_INFO("Action finished: %s",state.toString().c_str());
00204 }
00205 else
00206 ROS_INFO("Action did not finish before the time out.");
00207 }
00208 return finished_before_timeout && success;
00209
00210 }
00211
00212 vector<double> Arm::getCurrentJointAngles(){
00213 updateJointStatePos();
00214 return current_joint_angles_;
00215 }
00216
00217 bool Arm::getIK(const geometry_msgs::PoseStamped& pose, vector<double>& joint_angles, vector<double>* ik_seed_pos){
00218 kinematics_msgs::GetPositionIK service_call;
00219
00220 if (ik_seed_pos){
00221 service_call.request.ik_request.ik_seed_state.joint_state.position = *ik_seed_pos;
00222 }else{
00223
00224 service_call.request.ik_request.ik_seed_state.joint_state.position = getCurrentJointAngles();
00225
00226 }
00227
00228 service_call.request.timeout = ros::Duration(5.0);
00229 service_call.request.ik_request.ik_seed_state.joint_state.name = joint_names;
00230 service_call.request.ik_request.pose_stamped = pose;
00231 service_call.request.ik_request.ik_link_name = armside_str +"_wrist_roll_link";
00232 if (!ik_service_client_.call(service_call)){
00233 ROS_ERROR("ik_service_call failed");
00234 return false;
00235 }
00236
00237 if (service_call.response.error_code.val != 1){
00238 ROS_ERROR("Could not get valid IK: error code %d", service_call.response.error_code.val);
00239 return false;
00240 }
00241
00242 joint_angles = service_call.response.solution.joint_state.position;
00243 return true;
00244
00245 }
00246
00247
00248
00249 bool Arm::moveWristRollLinktoPose(const geometry_msgs::PoseStamped& pose, double max_time, bool wait, vector<double>* ik_seed_pos ){
00250
00251 vector<double> joint_angles;
00252 if (!getIK(pose ,joint_angles , ik_seed_pos)){
00253 return false;
00254 }
00255
00256 return goToJointPos(joint_angles, max_time, wait );
00257
00258 }
00259
00260
00261 bool Arm::goToJointPos (const double* positions , int num_positions, double max_time , bool wait ){
00262 std::vector<double> pos_vec (positions, positions + 7 * num_positions);
00263 return goToJointPos(pos_vec, max_time, wait);
00264 }
00265
00266 bool Arm::goToJointPos (const vector<double>& positions , double max_time, bool wait ){
00267
00268 if (positions.size() % 7 != 0){
00269 ROS_ERROR("you must specify 7 (or a multiple thereof) for the arm joint positions");
00270 }
00271
00272 pr2_controllers_msgs::JointTrajectoryGoal goal;
00273 goal.trajectory.joint_names = joint_names;
00274 unsigned int num_waypoints = positions.size() / 7;
00275 goal.trajectory.points.resize(num_waypoints);
00276 vector<double>::const_iterator it = positions.begin();
00277 vector<double>::const_iterator it_end = positions.begin() + 7;
00278
00279 for (unsigned int i=0; i <num_waypoints; i++){
00280
00281 goal.trajectory.points[i].positions.insert(goal.trajectory.points[i].positions.begin(), it, it_end);
00282 goal.trajectory.points[i].velocities.resize(7);
00283 goal.trajectory.points[i].time_from_start = ros::Duration( (i+1) * max_time / num_waypoints);
00284 it =it_end;
00285 it_end+=7;
00286 }
00287
00288
00289 goal.trajectory.header.stamp = ros::Time::now();
00290 ROS_INFO("sending goal");
00291 traj_client_.sendGoal(goal);
00292 bool finished_before_timeout = false;
00293 if (wait){
00294 finished_before_timeout =traj_client_.waitForResult(ros::Duration(3*max_time));
00295 if (finished_before_timeout)
00296 {
00297 actionlib::SimpleClientGoalState state = traj_client_.getState();
00298 ROS_INFO("move to joint pos Action finished: %s",state.toString().c_str());
00299 }
00300 else
00301 ROS_INFO("move to joint pos Action did not finish before the time out.");
00302
00303 }
00304
00305 return finished_before_timeout;
00306 }
00307
00308 bool Arm::updateJointStatePos(){
00309 simple_robot_control::ReturnJointStates req;
00310 req.request.name = joint_names;
00311
00312 if(!ros::service::waitForService("return_joint_states", ros::Duration(5.0))){
00313 ROS_ERROR("Arm:Could not contact return_joint_states service. Did you run joint_state_listner?");
00314 return false;
00315 }
00316 if (!ros::service::call("return_joint_states",req)){
00317 ROS_ERROR("Arm service call failed");
00318 }
00319 current_joint_angles_= req.response.position;
00320 return true;
00321
00322 }
00323
00324
00325 bool Arm::rotateWrist(double radians, double wrist_speed ,bool wait){
00326
00327
00328 updateJointStatePos();
00329 vector<double> new_pos = current_joint_angles_;
00330 new_pos[6] += radians;
00331 return goToJointPos(new_pos, std::abs(radians) / 2 / 3.14 * wrist_speed, wait);
00332
00333
00334 }
00335
00336 bool Arm::isAtPos(const std::vector<double>& pos_vec){
00337 const double epsilon= 0.1;
00338 updateJointStatePos();
00339 int pos = pos_vec.size() - 7;
00340 for (int i=0; i<7; i++){
00341 printf ("curent pos %f pos_vec %f \n", current_joint_angles_[i], pos_vec[pos + i] );
00342 if (std::abs(current_joint_angles_[i] - pos_vec[pos + i]) > epsilon)
00343 return false;
00344 }
00345 return true;
00346 }
00347
00348 bool Arm::tuck(){
00349
00350 ROS_INFO("tucking arm %s", armside_str.c_str());
00351 std::vector<double> tuck_pos_vec;
00352 if (armside_str == "r"){
00353 double tuck_pos[] = { -0.4,0.0,0.0,-2.25,0.0,0.0,0.0, -0.01,1.35,-1.92,-1.68, 1.35,-0.18,0.31};
00354 tuck_pos_vec.insert(tuck_pos_vec.begin(),tuck_pos, tuck_pos+14);
00355 }else{
00356 double tuck_pos[] = { 0.4,0.0,0.0,-2.25,0.0,0.0,0.0, -0.05,1.31,1.38,-2.06,1.69,-2.02,2.44};
00357 tuck_pos_vec.insert(tuck_pos_vec.begin(),tuck_pos, tuck_pos+14);
00358 }
00359 if (!isAtPos(tuck_pos_vec)){
00360 return goToJointPos(tuck_pos_vec);
00361 }
00362 ROS_INFO(" arm %s is already in tucked pos", armside_str.c_str());
00363 return true;
00364
00365 }
00366
00367 bool Arm::stretch(){
00368
00369 ROS_INFO("stretching arm %s", armside_str.c_str());
00370 std::vector<double> tuck_pos_vec;
00371 if (armside_str == "r"){
00372 double tuck_pos[] = {-1.634, -0.039, -0.324, -0.131, 31.779, 0.004, 24.986};
00373 tuck_pos_vec.insert(tuck_pos_vec.begin(),tuck_pos, tuck_pos+7);
00374 }else{
00375 double tuck_pos[] = { 1.613, -0.105, 0.336, -0.033, -6.747, 0.014, 0.295};
00376 tuck_pos_vec.insert(tuck_pos_vec.begin(),tuck_pos, tuck_pos+7);
00377 }
00378 if (!isAtPos(tuck_pos_vec)){
00379 return goToJointPos(tuck_pos_vec);
00380 }
00381 ROS_INFO(" arm %s is already in tucked pos", armside_str.c_str());
00382 return true;
00383
00384 }
00385
00386
00387 tf::StampedTransform Arm::gripperToWrist(const tf::StampedTransform& pose){
00388 tf::Vector3 offset(gripperlength,0,0);
00389 tf::Transform rot(pose.getRotation());
00390 tf::StampedTransform out( tf::Transform(pose.getRotation(), pose.getOrigin() - rot * offset) , pose.stamp_, pose.frame_id_, pose.child_frame_id_);
00391 return out;
00392 }
00393
00394 tf::StampedTransform Arm::wristToGripper(const tf::StampedTransform& pose){
00395 tf::Vector3 offset(gripperlength,0,0);
00396 tf::Transform rot(pose.getRotation());
00397 tf::StampedTransform out( tf::Transform(pose.getRotation(), pose.getOrigin() + rot * offset) , pose.stamp_, pose.frame_id_, pose.child_frame_id_);
00398 return out;
00399 }
00400
00401
00402 tf::StampedTransform Arm::makePose(const tf::Vector3& position, string frame_id, approach_direction_t approach){
00403
00404
00405 tf::StampedTransform tf(tf::Transform(tf::Quaternion(0,0,0,1), position), ros::Time(), frame_id, "/doesntmatter");
00406 tf::TransformListener tf_listener;
00407 tf::StampedTransform tf_sourceframe_in_baselink;
00408
00409 tf_listener.waitForTransform( "/base_link", tf.frame_id_, ros::Time(0), ros::Duration(0.5));
00410 tf_listener.lookupTransform( "/base_link", tf.frame_id_, ros::Time(), tf_sourceframe_in_baselink);
00411 tf::StampedTransform tf_pose_in_baselink (tf::Transform(tf_sourceframe_in_baselink * tf), tf.stamp_, "/base_link", "/doesntmatter") ;
00412
00413 switch (approach){
00414
00415 case (FRONTAL):
00416 tf_pose_in_baselink.setRotation(tf::Quaternion( 0, 0 , 0, 1)); break;
00417 case (FROM_BELOW):
00418 tf_pose_in_baselink.setRotation(tf::Quaternion( HALF_SQRT_TWO , 0, HALF_SQRT_TWO , 0)); break;
00419 case (FROM_RIGHT_SIDEWAYS):
00420 tf_pose_in_baselink.setRotation(tf::Quaternion( 0 , 0, HALF_SQRT_TWO , HALF_SQRT_TWO)); break;
00421 case (FROM_RIGHT_UPRIGHT):
00422 tf_pose_in_baselink.setRotation(tf::Quaternion( -0.5 , -0.5, 0.5 , 0.5)); break;
00423 case (FROM_ABOVE):
00424 tf_pose_in_baselink.setRotation(tf::Quaternion( HALF_SQRT_TWO , 0, -HALF_SQRT_TWO , 0)); break;
00425 case (FROM_LEFT_SIDEWAYS):
00426 tf_pose_in_baselink.setRotation(tf::Quaternion( -HALF_SQRT_TWO , HALF_SQRT_TWO , 0 , 0)); break;
00427 case (FROM_LEFT_UPRIGHT):
00428 tf_pose_in_baselink.setRotation(tf::Quaternion( -0.5 , 0.5, -0.5 , 0.5)); break;
00429 }
00430
00431 return tf_pose_in_baselink;
00432
00433 }
00434
00435
00436 bool Arm::moveGripperToPosition(const tf::Vector3& position, string frame_id, approach_direction_t approach, double max_time , bool wait, vector<double>* ik_seed_pos ){
00437
00438 tf::StampedTransform tf_pose_in_baselink_new(gripperToWrist(makePose(position, frame_id, approach)));
00439 return moveWristRollLinktoPose(tf_pose_in_baselink_new, max_time, wait, ik_seed_pos);
00440 }
00441
00442
00443
00444
00445 bool Arm::moveGrippertoPose(const tf::StampedTransform& tf, double max_time, bool wait, vector<double>* ik_seed_pos ){
00446
00447
00448 tf::StampedTransform tf_new(gripperToWrist(tf));
00449 return moveWristRollLinktoPose(tf_new, max_time, wait, ik_seed_pos);
00450
00451 }
00452
00453 bool Arm::moveGrippertoPoseWithCollisionChecking(const tf::StampedTransform& tf, double max_time, bool wait, std::string planner ){
00454
00455
00456 tf::StampedTransform tf_new(gripperToWrist(tf));
00457 return moveWristRollLinktoPoseWithCollisionChecking(tf_new, max_time, wait, planner);
00458
00459 }
00460
00461 bool Arm::moveGrippertoPositionWithCollisionChecking(const tf::Vector3& position, string frame_id, approach_direction_t approach, double max_time, bool wait,std::string planner ){
00462
00463
00464 tf::StampedTransform tf_pose_in_baselink_new(gripperToWrist(makePose(position, frame_id, approach)));
00465 return moveWristRollLinktoPoseWithCollisionChecking(tf_pose_in_baselink_new, max_time, wait,planner);
00466
00467 }
00468
00469 bool Arm::moveGrippertoPoseWithOrientationConstraints(const tf::StampedTransform& tf, bool keep_roll, bool keep_pitch, bool keep_yaw, double max_time, bool wait, double tolerance ){
00470
00471 tf::StampedTransform tf_new(gripperToWrist(tf));
00472 return moveWristRollLinktoPoseWithOrientationConstraints(tf_new, keep_roll, keep_pitch, keep_yaw, max_time, wait);
00473
00474 }
00475
00476
00477 bool Arm::moveWristRollLinktoPoseWithOrientationConstraints(const tf::StampedTransform& tf, bool keep_roll, bool keep_pitch, bool keep_yaw, double max_time, bool wait, double tolerance ){
00478 geometry_msgs::PoseStamped pose;
00479 tf::Stamped<tf::Pose> tf_pose(tf,tf.stamp_, tf.frame_id_);
00480
00481 tf::poseStampedTFToMsg(tf_pose,pose);
00482 return moveWristRollLinktoPoseWithOrientationConstraints(pose, keep_roll, keep_pitch, keep_yaw, max_time, wait, tolerance);
00483 }
00484
00485
00486 bool Arm::moveWristRollLinktoPoseWithOrientationConstraints(const geometry_msgs::PoseStamped& pose, bool keep_roll, bool keep_pitch, bool keep_yaw, double max_time, bool wait, double tolerance ){
00487 if (!move_arm_client_){
00488 ROS_ERROR("collision checking arm server has not been started");
00489 return false;
00490 }
00491 bool finished_before_timeout = true;
00492 move_arm_msgs::MoveArmGoal goalA;
00493
00494 goalA.motion_plan_request.group_name = group_name;
00495 goalA.motion_plan_request.num_planning_attempts = 1;
00496 goalA.motion_plan_request.planner_id = std::string("");
00497 goalA.planner_service_name = std::string("ompl_planning/plan_kinematic_path");
00498 goalA.motion_plan_request.allowed_planning_time = ros::Duration(25.0);
00499
00500 goalA.motion_plan_request.goal_constraints.position_constraints.resize(1);
00501 goalA.motion_plan_request.goal_constraints.position_constraints[0].header.stamp = pose.header.stamp;
00502 goalA.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id =pose.header.frame_id ;
00503
00504 goalA.motion_plan_request.goal_constraints.position_constraints[0].link_name = armside_str + "_wrist_roll_link";
00505 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.x = pose.pose.position.x;
00506 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.y = pose.pose.position.y;
00507 goalA.motion_plan_request.goal_constraints.position_constraints[0].position.z = pose.pose.position.z;
00508
00509 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.type = geometric_shapes_msgs::Shape::BOX;
00510 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00511 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00512 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00513
00514 goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_orientation.w = 1.0;
00515 goalA.motion_plan_request.goal_constraints.position_constraints[0].weight = 1.0;
00516
00517
00518 goalA.motion_plan_request.goal_constraints.position_constraints.resize(1);
00519 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.stamp = pose.header.stamp;
00520 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.frame_id = pose.header.frame_id;
00521 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].link_name = armside_str + "_wrist_roll_link";
00522 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.x = pose.pose.orientation.x;
00523 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.y = pose.pose.orientation.y;
00524 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.z = pose.pose.orientation.z;
00525 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.w = pose.pose.orientation.w;
00526
00527 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.04;
00528 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.04;
00529 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_yaw_tolerance = 0.04;
00530
00531 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.04;
00532 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.04;
00533 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_yaw_tolerance = 0.04;
00534
00535 goalA.motion_plan_request.goal_constraints.orientation_constraints[0].weight = 1.0;
00536
00537
00538 goalA.motion_plan_request.path_constraints.orientation_constraints.resize(1);
00539 goalA.motion_plan_request.path_constraints.orientation_constraints[0].header.frame_id = pose.header.frame_id ;
00540 goalA.motion_plan_request.path_constraints.orientation_constraints[0].header.stamp = pose.header.stamp;
00541 goalA.motion_plan_request.path_constraints.orientation_constraints[0].link_name = armside_str + "_wrist_roll_link";
00542
00543 goalA.motion_plan_request.path_constraints.orientation_constraints[0].orientation.x = pose.pose.orientation.x;
00544 goalA.motion_plan_request.path_constraints.orientation_constraints[0].orientation.y = pose.pose.orientation.y;
00545 goalA.motion_plan_request.path_constraints.orientation_constraints[0].orientation.z = pose.pose.orientation.z;
00546 goalA.motion_plan_request.path_constraints.orientation_constraints[0].orientation.w = pose.pose.orientation.w;
00547
00548
00549
00550 goalA.motion_plan_request.path_constraints.orientation_constraints[0].type = motion_planning_msgs::OrientationConstraint::HEADER_FRAME;
00551 if (keep_roll)
00552 goalA.motion_plan_request.path_constraints.orientation_constraints[0].absolute_roll_tolerance = tolerance;
00553 else
00554 goalA.motion_plan_request.path_constraints.orientation_constraints[0].absolute_roll_tolerance = M_PI;
00555
00556 if (keep_pitch)
00557 goalA.motion_plan_request.path_constraints.orientation_constraints[0].absolute_pitch_tolerance = tolerance;
00558 else
00559 goalA.motion_plan_request.path_constraints.orientation_constraints[0].absolute_pitch_tolerance = M_PI;
00560
00561 if (keep_yaw)
00562 goalA.motion_plan_request.path_constraints.orientation_constraints[0].absolute_yaw_tolerance = tolerance;
00563 else
00564 goalA.motion_plan_request.path_constraints.orientation_constraints[0].absolute_yaw_tolerance = M_PI;
00565
00566
00567
00568 move_arm_client_->sendGoal(goalA);
00569
00570 if (wait){
00571 finished_before_timeout = move_arm_client_->waitForResult(ros::Duration(60.0));
00572 if (finished_before_timeout)
00573 {
00574 actionlib::SimpleClientGoalState state = move_arm_client_->getState();
00575 ROS_INFO("Action finished: %s",state.toString().c_str());
00576 }
00577 else{
00578 ROS_INFO("Action did not finish before the time out.");
00579 return false;
00580 }
00581 }
00582
00583
00584
00585
00586
00587
00588
00589
00590
00591
00592
00593
00594
00595
00596
00597
00598
00599
00600
00601
00602
00603
00604
00605
00606
00607
00608
00609
00610
00611
00612
00613
00614
00615
00616
00617
00619 if( move_arm_client_->getState() == actionlib::SimpleClientGoalState::ABORTED){
00620 return false;
00621 }else{
00622 return true;
00623 }
00624
00625 }
00626
00627
00628 }