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 #include "pr2_doors_actions/action_release_handle.h"
00038 #include <tf/tf.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 actionlib;
00046
00047 static const string fixed_frame = "odom_combined";
00048
00049
00050 ReleaseHandleAction::ReleaseHandleAction(tf::TransformListener& tf) :
00051 tf_(tf),
00052 action_server_(ros::NodeHandle(),
00053 "release_handle",
00054 boost::bind(&ReleaseHandleAction::execute, this, _1)),
00055 gripper_action_client_("r_gripper_controller/gripper_action", true),
00056 ik_action_client_("r_arm_ik", true)
00057 {
00058 ros::NodeHandle node_private("~");
00059 double shoulder_pan_,shoulder_lift_,upper_arm_roll_,elbow_flex_,forearm_roll_,wrist_flex_,wrist_roll_;
00060 node_private.getParam("pose_suggestion/shoulder_pan", shoulder_pan_ );
00061 node_private.getParam("pose_suggestion/shoulder_lift", shoulder_lift_ );
00062 node_private.getParam("pose_suggestion/upper_arm_roll", upper_arm_roll_);
00063 node_private.getParam("pose_suggestion/elbow_flex", elbow_flex_);
00064 node_private.getParam("pose_suggestion/forearm_roll", forearm_roll_);
00065 node_private.getParam("pose_suggestion/wrist_flex", wrist_flex_);
00066 node_private.getParam("pose_suggestion/wrist_roll", wrist_roll_);
00067
00068 ik_goal_.ik_seed.name.push_back("r_shoulder_pan_joint");
00069 ik_goal_.ik_seed.name.push_back("r_shoulder_lift_joint");
00070 ik_goal_.ik_seed.name.push_back("r_upper_arm_roll_joint");
00071 ik_goal_.ik_seed.name.push_back("r_elbow_flex_joint");
00072 ik_goal_.ik_seed.name.push_back("r_forearm_roll_joint");
00073 ik_goal_.ik_seed.name.push_back("r_wrist_flex_joint");
00074 ik_goal_.ik_seed.name.push_back("r_wrist_roll_joint");
00075 ik_goal_.ik_seed.position.push_back(shoulder_pan_);
00076 ik_goal_.ik_seed.position.push_back(shoulder_lift_);
00077 ik_goal_.ik_seed.position.push_back(upper_arm_roll_);
00078 ik_goal_.ik_seed.position.push_back(elbow_flex_);
00079 ik_goal_.ik_seed.position.push_back(forearm_roll_);
00080 ik_goal_.ik_seed.position.push_back(wrist_flex_);
00081 ik_goal_.ik_seed.position.push_back(wrist_roll_);
00082 };
00083
00084
00085 ReleaseHandleAction::~ReleaseHandleAction()
00086 {};
00087
00088
00089
00090 void ReleaseHandleAction::execute(const door_msgs::DoorGoalConstPtr& goal)
00091 {
00092 ROS_INFO("ReleaseHandleAction: execute");
00093
00094
00095 ROS_INFO("ReleaseHandleAction: open the gripper");
00096 pr2_controllers_msgs::Pr2GripperCommandGoal gripper_msg;
00097 gripper_msg.command.position = 0.07;
00098 gripper_msg.command.max_effort = 10000.0;
00099
00100
00101 int MAX_OPEN_GRIPPER_RETRIES = 5;
00102 int open_gripper_retry = 0;
00103 while (gripper_action_client_.sendGoalAndWait(gripper_msg, ros::Duration(20.0), ros::Duration(5.0)) != SimpleClientGoalState::SUCCEEDED){
00104
00105 if (open_gripper_retry >= MAX_OPEN_GRIPPER_RETRIES) {
00106 ROS_ERROR("Release handle: gripper failed to open");
00107 action_server_.setAborted();
00108 return;
00109 }
00110
00111 open_gripper_retry++;
00112 ROS_INFO("Release handle: Failed to open gripper to %fm, retry attempt #%d",gripper_msg.command.position,open_gripper_retry);
00113
00114 }
00115
00116
00117 ros::Time time = ros::Time::now();
00118 if (!tf_.waitForTransform("base_link", "r_wrist_roll_link", time, ros::Duration(3.0))){
00119 ROS_ERROR("Release handle: Failed to get transform between base_link and r_wrist_roll_link");
00120 action_server_.setAborted();
00121 return;
00122 }
00123 tf::StampedTransform gripper_pose;
00124 tf_.lookupTransform("base_link", "r_wrist_roll_link", time, gripper_pose);
00125 tf::Transform gripper_offset(tf::Quaternion::getIdentity() ,tf::Vector3(-0.06,0,0));
00126
00127
00128
00129 ROS_INFO("Release handle: move away from door handle");
00130 tf::poseStampedTFToMsg(tf::Stamped<tf::Transform>(gripper_pose * gripper_offset, time, "base_link"),
00131 ik_goal_.pose);
00132 if (ik_action_client_.sendGoalAndWait(ik_goal_, ros::Duration(20.0), ros::Duration(5.0)) != SimpleClientGoalState::SUCCEEDED) {
00133 ROS_ERROR("Release handle: failed to move away from door handle");
00134 action_server_.setAborted();
00135 return;
00136 }
00137
00138 action_result_.door = goal->door;
00139 action_server_.setSucceeded(action_result_);
00140 }
00141
00142
00143