action_touch_door.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 n * Software License Agreement (BSD License)
00003  * 
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  * 
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  * 
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  * 
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Wim Meeussen */
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   // transform door message to time fixed frame
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   // check for preemption
00080   if (action_server_.isPreemptRequested()){
00081     ROS_ERROR("TouchDoorAction: preempted");
00082     action_server_.setPreempted();
00083     return;
00084   }
00085 
00086   // close the gripper 
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   // get gripper position that is feasable for the robot arm
00097   StampedTransform shoulder_pose; tf_.lookupTransform(goal_tr.header.frame_id, "r_shoulder_pan_link", Time(), shoulder_pose);
00098   // this check does not make sense because we're not tracking the door angle while opinging
00099   //double angle = getNearestDoorAngle(shoulder_pose, goal_tr, 0.75, touch_dist);
00100   //if (fabs(angle) > fabs(getDoorAngle(goal_tr))){
00101   //  ROS_ERROR("Door touch pose for the gripper is inside the door");
00102   //  return robot_actions::ABORTED;
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   //req_moveto.tolerance.vel.x = 0.1;
00108   //req_moveto.tolerance.vel.y = 0.1;
00109   //req_moveto.tolerance.vel.z = 0.1;
00110 
00111   // move gripper in front of door
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 


pr2_doors_actions
Author(s): Wim Meeussen
autogenerated on Wed Dec 11 2013 14:17:44