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_touch_door.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 touch_dist = 0.65;
00050 static const double gripper_effort = 100;
00051
00052
00053 TouchDoorAction::TouchDoorAction(tf::TransformListener& tf) :
00054 tf_(tf),
00055 action_server_(ros::NodeHandle(),
00056 "touch_door",
00057 boost::bind(&TouchDoorAction::execute, this, _1)),
00058 gripper_action_client_("r_gripper_controller/gripper_action", true)
00059 {};
00060
00061
00062 TouchDoorAction::~TouchDoorAction()
00063 {};
00064
00065
00066 void TouchDoorAction::execute(const door_msgs::DoorGoalConstPtr& goal)
00067 {
00068 ROS_INFO("TouchDoorAction: execute");
00069
00070
00071 door_msgs::Door goal_tr;
00072 if (!transformTo(tf_, fixed_frame, goal->door, goal_tr, fixed_frame)){
00073 ROS_ERROR("Could not tranform door message from '%s' to '%s' at time %f",
00074 goal->door.header.frame_id.c_str(), fixed_frame.c_str(), goal->door.header.stamp.toSec());
00075 action_server_.setPreempted();
00076 return;
00077 }
00078
00079
00080 if (action_server_.isPreemptRequested()){
00081 ROS_ERROR("TouchDoorAction: preempted");
00082 action_server_.setPreempted();
00083 return;
00084 }
00085
00086
00087 pr2_controllers_msgs::Pr2GripperCommandGoal gripper_msg;
00088 gripper_msg.command.position = 0.0;
00089 gripper_msg.command.max_effort = gripper_effort;
00090 if (gripper_action_client_.sendGoalAndWait(gripper_msg, ros::Duration(10.0), ros::Duration(5.0)) != SimpleClientGoalState::SUCCEEDED){
00091 ROS_ERROR("TouchDoorAction: gripper failed to close");
00092 action_server_.setPreempted();
00093 return;
00094 }
00095
00096
00097 StampedTransform shoulder_pose; tf_.lookupTransform(goal_tr.header.frame_id, "r_shoulder_pan_link", Time(), shoulder_pose);
00098
00099
00100
00101
00102
00103
00104 Stamped<Pose> gripper_pose = getGripperPose(goal_tr, getNearestDoorAngle(shoulder_pose, goal_tr, 0.75, touch_dist), touch_dist);
00105 gripper_pose.stamp_ = Time::now();
00106 poseStampedTFToMsg(gripper_pose, req_moveto.pose);
00107
00108
00109
00110
00111
00112 ROS_INFO("move to touch the door at distance %f from hinge", touch_dist);
00113 if (!ros::service::call("r_arm_constraint_cartesian_trajectory_controller/move_to", req_moveto, res_moveto)){
00114 ROS_ERROR("move_to command failed");
00115 action_server_.setPreempted();
00116 return;
00117 }
00118
00119 action_result_.door = goal->door;
00120 action_server_.setSucceeded(action_result_);
00121 }
00122
00123