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 #include <pr2_doors_common/door_functions.h>
00038 #include "pr2_doors_actions/action_grasp_handle.h"
00039 
00040 using namespace tf;
00041 using namespace KDL;
00042 using namespace ros;
00043 using namespace std;
00044 using namespace door_handle_detector;
00045 using namespace pr2_doors_common;
00046 using namespace actionlib;
00047 
00048 static const string fixed_frame = "odom_combined";
00049 static const double gripper_effort = 100;
00050 
00051 
00052 
00053 GraspHandleAction::GraspHandleAction(tf::TransformListener& tf) : 
00054   tf_(tf),
00055   action_server_(ros::NodeHandle(), 
00056                  "grasp_handle", 
00057                  boost::bind(&GraspHandleAction::execute, this, _1)),
00058   gripper_action_client_("r_gripper_controller/gripper_action", true),
00059   ik_action_client_("r_arm_ik", true)
00060 {
00061   ros::NodeHandle node_private("~");
00062   double shoulder_pan_,shoulder_lift_,upper_arm_roll_,elbow_flex_,forearm_roll_,wrist_flex_,wrist_roll_;
00063   node_private.getParam("pose_suggestion/shoulder_pan", shoulder_pan_ );
00064   node_private.getParam("pose_suggestion/shoulder_lift", shoulder_lift_ );
00065   node_private.getParam("pose_suggestion/upper_arm_roll", upper_arm_roll_);
00066   node_private.getParam("pose_suggestion/elbow_flex", elbow_flex_);
00067   node_private.getParam("pose_suggestion/forearm_roll", forearm_roll_);
00068   node_private.getParam("pose_suggestion/wrist_flex",  wrist_flex_);
00069   node_private.getParam("pose_suggestion/wrist_roll",  wrist_roll_);
00070     
00071   ik_goal_.ik_seed.name.push_back("r_shoulder_pan_joint");
00072   ik_goal_.ik_seed.name.push_back("r_shoulder_lift_joint");
00073   ik_goal_.ik_seed.name.push_back("r_upper_arm_roll_joint");
00074   ik_goal_.ik_seed.name.push_back("r_elbow_flex_joint");
00075   ik_goal_.ik_seed.name.push_back("r_forearm_roll_joint");
00076   ik_goal_.ik_seed.name.push_back("r_wrist_flex_joint");
00077   ik_goal_.ik_seed.name.push_back("r_wrist_roll_joint");
00078   ik_goal_.ik_seed.position.push_back(shoulder_pan_);
00079   ik_goal_.ik_seed.position.push_back(shoulder_lift_);
00080   ik_goal_.ik_seed.position.push_back(upper_arm_roll_);
00081   ik_goal_.ik_seed.position.push_back(elbow_flex_);
00082   ik_goal_.ik_seed.position.push_back(forearm_roll_);
00083   ik_goal_.ik_seed.position.push_back(wrist_flex_);
00084   ik_goal_.ik_seed.position.push_back(wrist_roll_);
00085 };
00086 
00087 
00088 GraspHandleAction::~GraspHandleAction()
00089 {};
00090 
00091 
00092 
00093 void GraspHandleAction::execute(const door_msgs::DoorGoalConstPtr& goal)
00094 {
00095   ROS_INFO("GraspHandleAction: execute");
00096 
00097   
00098   door_msgs::Door goal_tr;
00099   if (!transformTo(tf_, fixed_frame, goal->door, goal_tr, fixed_frame)){
00100     ROS_ERROR("GraspHandleAction: Could not tranform door message from '%s' to '%s' at time %f",
00101               goal->door.header.frame_id.c_str(), fixed_frame.c_str(), goal->door.header.stamp.toSec());
00102     action_server_.setAborted();
00103     return;
00104   }
00105 
00106   Vector x_axis(1,0,0);
00107   Vector normal = getDoorNormal(goal_tr);
00108   Vector wrist_pos_approach = normal*-0.25; 
00109   Vector wrist_pos_grasp = normal*-0.15; 
00110   Vector handle(goal_tr.handle.x, goal_tr.handle.y, goal_tr.handle.z);
00111   Stamped<Pose> gripper_pose;
00112   gripper_pose.frame_id_ = fixed_frame;
00113   
00114   
00115   if (action_server_.isPreemptRequested()){
00116     ROS_ERROR("GraspHandleAction: preempted");
00117     action_server_.setPreempted();
00118     return;
00119   }
00120   
00121   
00122   pr2_controllers_msgs::Pr2GripperCommandGoal gripper_msg;
00123   gripper_msg.command.position = 0.07;
00124   gripper_msg.command.max_effort = gripper_effort;
00125 
00126   int MAX_OPEN_GRIPPER_RETRIES = 5;
00127   int open_gripper_retry = 0;
00128   while (gripper_action_client_.sendGoalAndWait(gripper_msg, ros::Duration(20.0), ros::Duration(5.0)) != SimpleClientGoalState::SUCCEEDED){
00129 
00130     if (open_gripper_retry >= MAX_OPEN_GRIPPER_RETRIES) {
00131       ROS_ERROR("GraspHandleAction: OPEN DOOR DEMO FAILED due to GraspHandleAction failure: gripper failed to open");
00132       action_server_.setAborted();
00133       return;
00134     }
00135 
00136     open_gripper_retry++;
00137     ROS_INFO("Failed to open gripper to %fm, retry attempt #%d",gripper_msg.command.position,open_gripper_retry);
00138 
00139   }
00140 
00141 
00142   
00143   gripper_pose.setOrigin( Vector3(handle(0) + wrist_pos_approach(0), handle(1) + wrist_pos_approach(1),handle(2) + wrist_pos_approach(2)));
00144   gripper_pose.setRotation( tf::createQuaternionFromRPY(M_PI/2.0, 0, getVectorAngle(x_axis, normal)) ); 
00145   gripper_pose.stamp_ = Time::now();
00146   poseStampedTFToMsg(gripper_pose, ik_goal_.pose);
00147   ROS_INFO("GraspHandleAction: move in front of handle");
00148   if (ik_action_client_.sendGoalAndWait(ik_goal_, ros::Duration(20.0), ros::Duration(5.0)) != SimpleClientGoalState::SUCCEEDED) {
00149     ROS_ERROR("GraspHandleAction: failed to move gripper in front of handle");
00150     ros::Duration(5.0).sleep();
00151     gripper_pose.stamp_ = Time::now();
00152     poseStampedTFToMsg(gripper_pose, ik_goal_.pose);
00153     
00154     
00155   }
00156 
00157   
00158   gripper_pose.frame_id_ = fixed_frame;
00159   gripper_pose.setOrigin( Vector3(handle(0) + wrist_pos_grasp(0), handle(1) + wrist_pos_grasp(1),handle(2) + wrist_pos_grasp(2)));
00160   gripper_pose.stamp_ = Time::now();
00161   poseStampedTFToMsg(gripper_pose, ik_goal_.pose);
00162   ROS_INFO("GraspHandleAction: move over handle");
00163   if (ik_action_client_.sendGoalAndWait(ik_goal_, ros::Duration(20.0), ros::Duration(5.0)) != SimpleClientGoalState::SUCCEEDED) {  
00164     ROS_ERROR("Failure is not a problem here.");
00165     
00166   }
00167   
00168   
00169   gripper_msg.command.position = 0.0;
00170   if (gripper_action_client_.sendGoalAndWait(gripper_msg, ros::Duration(20.0), ros::Duration(5.0)) != SimpleClientGoalState::SUCCEEDED){
00171     ROS_INFO("GraspHandleAction: gripper failed to close all the way, might be holding the handle");
00172     if (gripper_action_client_.getResult()->stalled)
00173     {
00174       ROS_INFO("GraspHandleAction: gripper failed to close all the way but is stalled, possibly holding a handle?");
00175     }
00176     else
00177     {
00178       ROS_INFO("GraspHandleAction: gripper failed to close all the way and is not stalled");
00179       action_server_.setAborted();
00180       return;
00181     }
00182   }
00183 
00184   action_result_.door = goal_tr;
00185   action_server_.setSucceeded(action_result_);  
00186 }
00187 
00188